<?xml version="1.0"?> <robot name="turtlebot3_waffle_pi_sim" xmlns:xacro="http://ros.org/wiki/xacro"> <xacro:arg name="laser_visual" default="false"/> <xacro:arg name="camera_visual" default="false"/> <xacro:arg name="imu_visual" default="false"/> <gazebo reference="base_link"> <material>Gazebo/DarkGrey</material> </gazebo> <gazebo reference="wheel_left_link"> <mu1>0.1</mu1> <mu2>0.1</mu2> <kp>500000.0</kp> <kd>10.0</kd> <minDepth>0.001</minDepth> <maxVel>0.1</maxVel> <fdir1>1 0 0</fdir1> <material>Gazebo/FlatBlack</material> </gazebo> <gazebo reference="wheel_right_link"> <mu1>0.1</mu1> <mu2>0.1</mu2> <kp>500000.0</kp> <kd>10.0</kd> <minDepth>0.001</minDepth> <maxVel>0.1</maxVel> <fdir1>1 0 0</fdir1> <material>Gazebo/FlatBlack</material> </gazebo> <gazebo reference="caster_back_right_link"> <mu1>0.1</mu1> <mu2>0.1</mu2> <kp>1000000.0</kp> <kd>100.0</kd> <minDepth>0.001</minDepth> <maxVel>1.0</maxVel> <material>Gazebo/FlatBlack</material> </gazebo> <gazebo reference="caster_back_left_link"> <mu1>0.1</mu1> <mu2>0.1</mu2> <kp>1000000.0</kp> <kd>100.0</kd> <minDepth>0.001</minDepth> <maxVel>1.0</maxVel> <material>Gazebo/FlatBlack</material> </gazebo> <gazebo reference="imu_link"> <sensor type="imu" name="imu"> <always_on>true</always_on> <visualize>$(arg imu_visual)</visualize> </sensor> <material>Gazebo/Grey</material> </gazebo> <gazebo> <plugin name="turtlebot3_waffle_pi_controller" filename="libgazebo_ros_diff_drive.so"> <commandTopic>cmd_vel</commandTopic> <odometryTopic>odom</odometryTopic> <odometryFrame>odom</odometryFrame> <odometrySource>world</odometrySource> <publishOdomTF>true</publishOdomTF> <robotBaseFrame>base_footprint</robotBaseFrame> <publishWheelTF>false</publishWheelTF> <publishTf>true</publishTf> <publishWheelJointState>true</publishWheelJointState> <legacyMode>false</legacyMode> <updateRate>30</updateRate> <leftJoint>wheel_left_joint</leftJoint> <rightJoint>wheel_right_joint</rightJoint> <wheelSeparation>0.287</wheelSeparation> <wheelDiameter>0.066</wheelDiameter> <wheelAcceleration>1</wheelAcceleration> <wheelTorque>10</wheelTorque> <rosDebugLevel>na</rosDebugLevel> </plugin> </gazebo> <gazebo> <plugin name="imu_plugin" filename="libgazebo_ros_imu.so"> <alwaysOn>true</alwaysOn> <bodyName>imu_link</bodyName> <frameName>imu_link</frameName> <topicName>imu</topicName> <serviceName>imu_service</serviceName> <gaussianNoise>0.0</gaussianNoise> <updateRate>200</updateRate> <imu> <noise> <type>gaussian</type> <rate> <mean>0.0</mean> <stddev>2e-4</stddev> <bias_mean>0.0000075</bias_mean> <bias_stddev>0.0000008</bias_stddev> </rate> <accel> <mean>0.0</mean> <stddev>1.7e-2</stddev> <bias_mean>0.1</bias_mean> <bias_stddev>0.001</bias_stddev> </accel> </noise> </imu> </plugin> </gazebo> <gazebo reference="base_scan"> <material>Gazebo/FlatBlack</material> <sensor type="ray" name="lds_lfcd_sensor"> <pose>0 0 0 0 0 0</pose> <visualize>$(arg laser_visual)</visualize> <update_rate>5</update_rate> <ray> <scan> <horizontal> <samples>360</samples> <resolution>1</resolution> <min_angle>0.0</min_angle> <max_angle>6.28319</max_angle> </horizontal> </scan> <range> <min>0.120</min> <max>3.5</max> <resolution>0.015</resolution> </range> <noise> <type>gaussian</type> <mean>0.0</mean> <stddev>0.01</stddev> </noise> </ray> <plugin name="gazebo_ros_lds_lfcd_controller" filename="libgazebo_ros_laser.so"> <topicName>scan</topicName> <frameName>base_scan</frameName> </plugin> </sensor> </gazebo> <!--link : https://www.raspberrypi.org/documentation/hardware/camera/--> <gazebo reference="camera_rgb_frame"> <sensor type="camera" name="Pi Camera"> <always_on>true</always_on> <visualize>$(arg camera_visual)</visualize> <camera> <horizontal_fov>1.085595</horizontal_fov> <image> <width>640</width> <height>480</height> <format>R8G8B8</format> </image> <clip> <near>0.03</near> <far>100</far> </clip> </camera> <plugin name="camera_controller" filename="libgazebo_ros_camera.so"> <alwaysOn>true</alwaysOn> <updateRate>30.0</updateRate> <cameraName>camera</cameraName> <frameName>camera_rgb_optical_frame</frameName> <imageTopicName>rgb/image_raw</imageTopicName> <cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName> <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>