diff --git a/urdf/intel_realsense_d435.urdf.xacro b/urdf/intel_realsense_d435.urdf.xacro index ca1e8ee..743fe5a 100644 --- a/urdf/intel_realsense_d435.urdf.xacro +++ b/urdf/intel_realsense_d435.urdf.xacro @@ -24,8 +24,16 @@ name:=camera topic:=camera use_nominal_extrinsics:=false + namespace:=None simulation_engine:=ignition-gazebo"> + + + + + + + @@ -176,11 +184,12 @@ - + + true 30.0 - ${topic}/color/image_raw + ${ns}${topic}/color/image_raw false ${prefix}${name}_color_optical_frame @@ -194,13 +203,16 @@ 0.02 300.0 + + ${ns} + - + true 30.0 - ${topic}/depth + ${ns}${topic}/depth/image_rect_raw false ${prefix}${name}_depth_optical_frame @@ -221,6 +233,9 @@ 0.005 + + ${ns} + diff --git a/urdf/orbbec_astra.urdf.xacro b/urdf/orbbec_astra.urdf.xacro index f6f90f8..2927c44 100644 --- a/urdf/orbbec_astra.urdf.xacro +++ b/urdf/orbbec_astra.urdf.xacro @@ -94,16 +94,40 @@ - + + true - 20.0 + 30.0 + + ${ns}${camera_name}/color/image_raw + false + + ${prefix}${camera_name}_color_optical_frame + ${60.0/180.0*pi} + + 640 + 480 + + + + 0.6 + 8.0 + + + ${ns} + + - ${ns}${camera_name} - - ${prefix}${camera_name}_depth_optical_frame + + true + 10.0 - + + ${ns}${camera_name}/depth/image_raw + false + + ${prefix}${camera_name}_depth_optical_frame + ${60.0/180.0*pi} 640 @@ -114,6 +138,11 @@ 0.6 8.0 + + gaussian + 0.0 + 0.005 + ${ns} diff --git a/urdf/slamtec_rplidar_s3.urdf.xacro b/urdf/slamtec_rplidar_s3.urdf.xacro index a86d810..92866c1 100644 --- a/urdf/slamtec_rplidar_s3.urdf.xacro +++ b/urdf/slamtec_rplidar_s3.urdf.xacro @@ -112,10 +112,10 @@ 1 false + + ${ns} + - - ${ns} - diff --git a/urdf/stereolabs_zed.urdf.xacro b/urdf/stereolabs_zed.urdf.xacro index 288d81f..7971d70 100644 --- a/urdf/stereolabs_zed.urdf.xacro +++ b/urdf/stereolabs_zed.urdf.xacro @@ -22,12 +22,18 @@ + + + + + + + @@ -85,10 +91,10 @@ - + - + @@ -183,11 +189,11 @@ camera should be more accurate different frames and fovs can be set --> - + true 30.0 - ${model}/zed_node/rgb/image_rect_color + ${ns}${prefix}${name}/zed_node/rgb/image_rect_color false ${prefix}${name}_center_optical_frame @@ -203,13 +209,16 @@ 300.0 + + ${ns} + - + true 30.0 - ${model}/zed_node/depth + ${ns}${prefix}${name}/zed_node/depth false ${prefix}${name}_center_optical_frame @@ -229,6 +238,9 @@ 0.03 + + ${ns} + diff --git a/urdf/velodyne_puck.urdf.xacro b/urdf/velodyne_puck.urdf.xacro index e2a1f0a..a61c2e6 100644 --- a/urdf/velodyne_puck.urdf.xacro +++ b/urdf/velodyne_puck.urdf.xacro @@ -6,8 +6,16 @@ tf_prefix:=None topic:=scan frame_id:=velodyne + namespace:=None simulation_engine:=gazebo-classic"> + + + + + + + @@ -64,7 +72,7 @@ - + false 10.0 @@ -96,14 +104,10 @@ - ${topic} + ${ns}${topic} ${prefix}${frame_id} ${prefix}${frame_id} true - - ogre2 - @@ -117,7 +121,9 @@ ${prefix}${frame_id} - + + ${ns} +