<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="twil">
+ <xacro:arg name="d435" default="false" />
+
<xacro:property name="M_PI" value="3.1415926535897931" />
<xacro:include filename="$(find twil_description)/xacro/chassis.urdf.xacro" />
<xacro:include filename="$(find twil_description)/xacro/step_motor.urdf.xacro" />
<xacro:include filename="$(find twil_description)/xacro/sonar.urdf.xacro" />
- <!--> Added camera description <-->
- <xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro" />
+ <xacro:if value="$(arg d435)">
+ <xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro" />
+ </xacro:if>
<link name="twil_origin" />
<origin xyz="0.0 0.0 0.787" rpy="0.0 0.0 0.0" />
</joint>
- <xacro:sensor_d435 parent="tower">
- <origin xyz="0 0 0.876" rpy="0.0 0.0 0.0" />
- </xacro:sensor_d435>
-
- <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="${-M_PI/2} 0.0 ${-M_PI/2}" />
- </joint>
-
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so" >
<!-- <robotNamespace>/twil</robotNamespace> -->
</plugin>
</gazebo>
- <gazebo reference="camera_link">
- <sensor name="camera" type="depth">
- <update_rate>15</update_rate> <!--or 6 or 30 -->
- <camera>
- <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 -->
- <format>R8G8B8</format>
- </image>
- <clip>
- <near>0.05</near>
- <far>10</far>
- </clip>
- <noise>
- <type>gaussian</type>
- <mean>0.0</mean>
- <stddev>0.02</stddev>
- </noise>
- </camera>
-
- <plugin name="camera_plugin" filename="libgazebo_ros_openni_kinect.so">
- <baseline>0.05</baseline> <!-- dist between sensors -->
- <alwaysOn>true</alwaysOn>
- <!-- Keep this zero, update_rate in the parent <sensor> tag
- will control the frame rate. -->
- <updateRate>0.0</updateRate>
- <cameraName>camera</cameraName>
- <imageTopicName>/camera/depth/image_raw</imageTopicName>
- <cameraInfoTopicName>/camera/depth/camera_info</cameraInfoTopicName>
- <depthImageTopicName>/camera/depth/image_raw</depthImageTopicName>
- <depthImageInfoTopicName>/camera/depth/camera_info</depthImageInfoTopicName>
- <pointCloudTopicName>/camera/depth/points</pointCloudTopicName>
- <frameName>plugin_camera_link</frameName>
- <pointCloudCutoff>0.175</pointCloudCutoff> <!-- or 0.28 at 720p -->
- <pointCloudCutoffMax>10.0</pointCloudCutoffMax>
- <distortionK1>0</distortionK1>
- <distortionK2>0</distortionK2>
- <distortionK3>0</distortionK3>
- <distortionT1>0</distortionT1>
- <distortionT2>0</distortionT2>
- <CxPrime>0</CxPrime>
- <Cx>0</Cx>
- <Cy>0</Cy>
- <focalLength>0</focalLength>
- <hackBaseline>0</hackBaseline>
- </plugin>
- </sensor>
- </gazebo>
-
+ <xacro:if value="$(arg d435)">
+ <xacro:sensor_d435 parent="tower">
+ <origin xyz="0 0 0.876" rpy="0.0 0.0 0.0" />
+ </xacro:sensor_d435>
+
+ <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="${-M_PI/2} 0.0 ${-M_PI/2}" />
+ </joint>
+
+
+ <gazebo reference="camera_link">
+ <sensor name="camera" type="depth">
+ <update_rate>15</update_rate> <!--or 6 or 30 -->
+ <camera>
+ <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 -->
+ <format>R8G8B8</format>
+ </image>
+ <clip>
+ <near>0.05</near>
+ <far>10</far>
+ </clip>
+ <noise>
+ <type>gaussian</type>
+ <mean>0.0</mean>
+ <stddev>0.02</stddev>
+ </noise>
+ </camera>
+
+ <plugin name="camera_plugin" filename="libgazebo_ros_openni_kinect.so">
+ <baseline>0.05</baseline> <!-- dist between sensors -->
+ <alwaysOn>true</alwaysOn>
+ <!-- Keep this zero, update_rate in the parent <sensor> tag
+ will control the frame rate. -->
+ <updateRate>0.0</updateRate>
+ <cameraName>camera</cameraName>
+ <imageTopicName>/camera/depth/image_raw</imageTopicName>
+ <cameraInfoTopicName>/camera/depth/camera_info</cameraInfoTopicName>
+ <depthImageTopicName>/camera/depth/image_raw</depthImageTopicName>
+ <depthImageInfoTopicName>/camera/depth/camera_info</depthImageInfoTopicName>
+ <pointCloudTopicName>/camera/depth/points</pointCloudTopicName>
+ <frameName>plugin_camera_link</frameName>
+ <pointCloudCutoff>0.175</pointCloudCutoff> <!-- or 0.28 at 720p -->
+ <pointCloudCutoffMax>10.0</pointCloudCutoffMax>
+ <distortionK1>0</distortionK1>
+ <distortionK2>0</distortionK2>
+ <distortionK3>0</distortionK3>
+ <distortionT1>0</distortionT1>
+ <distortionT2>0</distortionT2>
+ <CxPrime>0</CxPrime>
+ <Cx>0</Cx>
+ <Cy>0</Cy>
+ <focalLength>0</focalLength>
+ <hackBaseline>0</hackBaseline>
+ </plugin>
+ </sensor>
+ </gazebo>
+ </xacro:if>
</robot>