<xacro:arg name="d435" default="false"/>
<xacro:if value="$(arg d435)">
- <xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro" />
- <xacro:sensor_d435 parent="awac_link">
- <origin xyz="0 0 0.175" rpy="0.0 0.0 ${pi/2}" />
+
+ <xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro"/>
+
+ <xacro:sensor_d435 parent="awac_link" use_nominal_extrinsics="false" add_plug="false" use_mesh="true">
+ <origin xyz="0 0 0.175" rpy="0.0 0.0 ${pi/2}"/>
</xacro:sensor_d435>
- <link name="plugin_camera_link" />
+ <link name="plugin_camera_link"/>
<joint name="plugin_camera_joint" type="fixed">
<parent link="camera_link"/>
- <child link="plugin_camera_link" />
- <origin xyz="0.0 0.0 0.0" rpy="${-pi/2} 0.0 ${-pi/2}" />
+ <child link="plugin_camera_link"/>
+ <origin xyz="0.0 0.0 0.0" rpy="${-pi/2} 0.0 ${-pi/2}"/>
</joint>
<gazebo reference="camera_link">
<sensor name="camera" type="depth">
<!--sensor name="camera" type="depth_camera"-->
- <always_on>trun</always_on>
- <update_rate>15</update_rate> <!--or 6 or 30 -->
+ <always_on>true</always_on>
+ <update_rate>15</update_rate> <!--or 6 or 30 -->
<visualize>false</visualize>
<triggered>false</triggered>
<trigger_topic>trigger</trigger_topic>
- <topic>depth_camera</topic> <!-- This is only used by Gazebo Ignition -->
+ <topic>depth_camera</topic> <!-- This is only used by Gazebo Ignition -->
<ignition_frame_id>camera_link</ignition_frame_id>
<camera>
- <horizontal_fov>1.309</horizontal_fov> <!--75 deg at 480p or 87 deg at 720p-->
+ <horizontal_fov>1.309</horizontal_fov> <!--75 deg at 480p or 87 deg at 720p-->
<image>
- <width>640</width> <!--or 1280 -->
- <height>480</height> <!--or 720 -->
+ <width>640</width> <!--or 1280 -->
+ <height>480</height> <!--or 720 -->
<format>R8G8B8</format>
<!--format>R_FLOAT32</format-->
</image>
<!-- Gazebo Classic -->
<xacro:if value="${hardware == 'gazebo'}">
<plugin name="camera_plugin" filename="libgazebo_ros_camera.so">
- <baseline>0.05</baseline> <!-- dist between sensors -->
+ <baseline>0.05</baseline> <!-- dist between sensors -->
<!-- Keep this zero, update_rate in the parent <sensor> tag
will control the frame rate. -->
<update_rate>0.0</update_rate>
<remapping>/camera/points:=camera/depth/points</remapping>
</ros>
<!--pointCloudCutoff>0.175</pointCloudCutoff--> <!-- or 0.28 at 720p -->
+ <min_depth>0.05</min_depth>
+ <max_depth>10</max_depth>
</plugin>
</xacro:if>
</sensor>