jumeau_pioneer3DX/Projet/pioneer_description/urdf/pioneer.gazebo

214 lines
6.6 KiB
Text
Raw Normal View History

<?xml version="1.0"?>
<robot>
<!-- ros_control plugin -->
<!--<gazebo>
<plugin name="differential_drive_controller" filename="libDiffDrivePlugin.so">
<updateRate>100.0</updateRate>
<robotNamespace>pioneer</robotNamespace>
<left_joint>base_left_wheel_joint</left_joint>
<right_joint>base_right_wheel_joint</right_joint>
<torque>200</torque>
<topicName>cmd_vel</topicName>
</plugin>
</gazebo>-->
<!-- START: Not sure if I need this, may allow for rosservice calls to gazebo joint manager -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>pioneer</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
<!-- END: Not sure if I need this -->
<gazebo>
<plugin filename="libgazebo_ros_diff_drive.so" name="differential_drive_controller">
<alwaysOn>true</alwaysOn>
<updateRate>100</updateRate>
<leftJoint>base_left_wheel_joint</leftJoint>
<rightJoint>base_right_wheel_joint</rightJoint>
<torque>5</torque>
<wheelSeparation>0.39</wheelSeparation>
<wheelDiameter>0.15</wheelDiameter>
<commandTopic>pioneer/cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<odometrySource>world</odometrySource>
<robotBaseFrame>base_link</robotBaseFrame>
<publishTf>true</publishTf>
<publishOdomTF>true</publishOdomTF>
<publishWheelTF>true</publishWheelTF>
<publishWheelJointState>true</publishWheelJointState>
<wheelAcceleration>0</wheelAcceleration>
<wheelTorque>5</wheelTorque>
<rosDebugLevel>na</rosDebugLevel>
<legacyMode>true</legacyMode>
</plugin>
</gazebo>
<!--<gazebo>
<plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
<updateRate>100.0</updateRate>
<robotNamespace>/pioneer</robotNamespace>
<leftFrontJoint>base_left_wheel_joint</leftFrontJoint>
<rightFrontJoint>base_right_wheel_joint</rightFrontJoint>
<leftRearJoint>base_left_wheel_joint</leftRearJoint>
<rightRearJoint>base_right_wheel_joint</rightRearJoint>
<wheelSeparation>0.39</wheelSeparation>
<wheelDiameter>0.15</wheelDiameter>
<robotBaseFrame>base_link</robotBaseFrame>
<torque>200</torque>
<topicName>cmd_vel</topicName>
</plugin>
</gazebo>-->
<!-- Chassis -->
<gazebo reference="chassis">
<material value="Gazebo/Red"/>
</gazebo>
<!-- Top -->
<gazebo reference="top_plate">
<material value="Gazebo/Black"/>
</gazebo>
<!-- Swivel -->
<gazebo reference="swivel">
<material value="Gazebo/Grey"/>
</gazebo>
<!-- Center Wheel + Hubcap -->
<gazebo reference="center_hubcap">
<material value="Gazebo/Grey"/>
</gazebo>
<gazebo reference="center_wheel">
<material value="Gazebo/Black"/>
</gazebo>
<gazebo reference="left_hub">
<material value="Gazebo/Yellow"/>
</gazebo>
<gazebo reference="left_wheel">
<material value="Gazebo/Black"/>
</gazebo>
<gazebo reference="right_hub">
<material value="Gazebo/Yellow"/>
</gazebo>
<gazebo reference="right_wheel">
<material value="Gazebo/Black"/>
</gazebo>
<!-- Front + Back Sonar -->
<gazebo reference="front_sonar">
<material value="Gazebo/Yellow"/>
</gazebo>
<gazebo reference="back_sonar">
<material value="Gazebo/Yellow"/>
</gazebo>
<!-- pilier -->
<gazebo reference="pilier_link">
<material value="Gazebo/Grey"/>
</gazebo>
<!-- plaque suport RPLIDAR -->
<gazebo reference="plaque_link">
<material value="Gazebo/Grey"/>
</gazebo>
<!-- OrbbecAstra -->
<gazebo reference="OrbbecAstra_link">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<material value="Gazebo/Grey"/>
</gazebo>
<!-- RPLIDAR-A2 -->
<gazebo reference="laser">
<material value="Gazebo/Black"/>
</gazebo>
<gazebo reference="laser">
<sensor type="ray" name="RPlidar_A2">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>40.0</update_rate>
<ray>
<scan>
<horizontal>
<samples>550</samples>
<resolution>1</resolution>
<min_angle>-3.1415</min_angle>
<max_angle>3.1415</max_angle>
</horizontal>
</scan>
<range>
<min>0.15</min>
<max>12.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<!-- Noise parameters based on published spec for Hokuyo laser achieving "+-30mm" accuracy at range < 10m. A mean of 0.0m and
stddev of 0.01m will put 99.7% of samples within 0.03m of the true reading. -->
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>base_scan</topicName>
<frameName>laser</frameName>
</plugin>
</sensor>
</gazebo>
<!-- OrbbecAstra -->
<gazebo reference="OrbbecAstra_link">
<sensor name="camera" type="depth">
<update_rate>30</update_rate>
<camera>
<horizontal_fov>1.047198</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.6</near>
<far>8</far>
</clip>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_openni_kinect.so">
<baseline>0.2</baseline>
<alwaysOn>true</alwaysOn>
<updateRate>1.0</updateRate>
<cameraName>camera_ir</cameraName>
<imageTopicName>/camera/color/image_raw</imageTopicName>
<cameraInfoTopicName>/camera/color/camera_info</cameraInfoTopicName>
<depthImageTopicName>/camera/depth/image_raw</depthImageTopicName>
<depthImageInfoTopicName>/camera/depth/camera_info</depthImageInfoTopicName>
<pointCloudTopicName>/camera/depth/points</pointCloudTopicName>
<frameName>OrbbecAstra_link</frameName>
<pointCloudCutoff>0.6</pointCloudCutoff>
<pointCloudCutoffMax>8.0</pointCloudCutoffMax>
<distortionK1>0.00000001</distortionK1>
<distortionK2>0.00000001</distortionK2>
<distortionK3>0.00000001</distortionK3>
<distortionT1>0.00000001</distortionT1>
<distortionT2>0.00000001</distortionT2>
<CxPrime>0</CxPrime>
<Cx>0</Cx>
<Cy>0</Cy>
<focalLength>0</focalLength>
<hackBaseline>0</hackBaseline>
</plugin>
</sensor>
</gazebo>
</robot>