2018-05-27 22:08:36 +05:30

85 lines
2.6 KiB
XML

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/line_follower</robotNamespace>
</plugin>
</gazebo>
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<alwaysOn>true</alwaysOn>
<legacyMode>false</legacyMode>
<updateRate>100</updateRate>
<leftJoint>left_wheel_hinge</leftJoint>
<rightJoint>right_wheel_hinge</rightJoint>
<wheelSeparation>${chassisWidth+wheelWidth}</wheelSeparation>
<wheelDiameter>${2*wheelRadius}</wheelDiameter>
<wheelTorque>20</wheelTorque>
<commandTopic>line_follower/cmd_vel</commandTopic>
<publishWheelTF>true</publishWheelTF>
<wheelAcceleration>1</wheelAcceleration>
<odometryTopic>line_follower/odom_diffdrive</odometryTopic>
<publishWheelJointState>true</publishWheelJointState>
<odometryFrame>odom</odometryFrame>
<publishTf>true</publishTf>
<odometrySource>1</odometrySource>
<robotBaseFrame>footprint</robotBaseFrame>
</plugin>
</gazebo>
<gazebo>
<plugin name="ground_truth" filename="libgazebo_ros_p3d.so">
<frameName>map</frameName>
<bodyName>chassis</bodyName>
<topicName>line_follower/odom</topicName>
<updateRate>30.0</updateRate>
</plugin>
</gazebo>
<gazebo reference="chassis">
<material>Gazebo/Orange</material>
</gazebo>
<gazebo reference="caster_wheel">
<mu1>0.0</mu1>
<mu2>0.0</mu2>
<material>Gazebo/Grey</material>
</gazebo>
<gazebo reference="camera">
<material>Gazebo/Grey</material>
<sensor type="camera" name="camera1">
<update_rate>30.0</update_rate>
<camera name="head">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>800</width>
<height>800</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>line_follower/camera1</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
</robot>