diff --git a/urdf/intel_realsense_d435.urdf.xacro b/urdf/intel_realsense_d435.urdf.xacro index 3ebd0ae..743fe5a 100644 --- a/urdf/intel_realsense_d435.urdf.xacro +++ b/urdf/intel_realsense_d435.urdf.xacro @@ -28,10 +28,10 @@ simulation_engine:=ignition-gazebo"> - + - + @@ -185,11 +185,11 @@ should be more accurate for D435 - different frames and fovs can be set --> - + true 30.0 - ${namespace_ext}${topic}/color/image_raw + ${ns}${topic}/color/image_raw false ${prefix}${name}_color_optical_frame @@ -204,15 +204,15 @@ 300.0 - ${namespace_ext} + ${ns} - + true 30.0 - ${namespace_ext}${topic}/depth/image_rect_raw + ${ns}${topic}/depth/image_rect_raw false ${prefix}${name}_depth_optical_frame @@ -234,7 +234,7 @@ - ${namespace_ext} + ${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}