一、运动控制:
- 两轮差速控制
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<legacyMode>false</legacyMode>
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<leftJoint>base_left_wheel_joint</leftJoint>
<rightJoint>base_right_wheel_joint</rightJoint>
<wheelSeparation>0.32</wheelSeparation>
<wheelDiameter>0.18</wheelDiameter>
<wheelTorque>5</wheelTorque>
<wheelAcceleration>0</wheelAcceleration>
<robotNamespace>pioneer</robotNamespace>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometrySource>ENCODER</odometrySource>
<odometryFrame>odom</odometryFrame>
<robotBaseFrame>base_link</robotBaseFrame>
<publishTf>1</publishTf>
<publishOdomTF>true</publishOdomTF>
<publishWheelTF>false</publishWheelTF>
<publishWheelJointState>false</publishWheelJointState>
<rosDebugLevel>Warn</rosDebugLevel>
</plugin>
</gazebo>
- 四轮差速控制
<gazebo>
<plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
<updateRate>100.0</updateRate>
<robotNamespace>/</robotNamespace>
<leftFrontJoint>front_left_wheel_joint</leftFrontJoint>
<rightFrontJoint>front_right_wheel_joint</rightFrontJoint>
<leftRearJoint>back_left_wheel_joint</leftRearJoint>
<rightRearJoint>back_right_wheel_joint</rightRearJoint>
<wheelSeparation>0.4</wheelSeparation>
<wheelDiameter>0.215</wheelDiameter>
<robotBaseFrame>base_link</robotBaseFrame>
<torque>20</torque>
<topicName>cmd_vel</topicName>
<broadcastTF>false</broadcastTF>
</plugin>
</gazebo>
- model 控制
使用geometry_msgs /Twist类型消息控制gazebo任意模型沿水平面移动(link、joint)。
<gazebo>
<plugin name="object_controller" filename="libgazebo_ros_planar_move.so">
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<odometryRate>20.0</odometryRate>
<robotBaseFrame>base_footprint</robotBaseFrame>
</plugin>
</gazebo>
二、Gazebo里程计
<gazebo>
<plugin name="p3d_base_controller" filename="libgazebo_ros_p3d.so">
<alwaysOn>true</alwaysOn>
<updateRate>50.0</updateRate>
<bodyName>base_link</bodyName>
<topicName>odom</topicName>
<gaussianNoise>0.01</gaussianNoise>
<frameName>world</frameName>
<xyzOffsets>0 0 0</xyzOffsets>
<rpyOffsets>0 0 0</rpyOffsets>
</plugin>
</gazebo>
三、传感器
- laser
<gazebo reference="hokuyo_link">
<sensor type="ray" name="head_hokuyo_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>1800</samples>
<resolution>1</resolution>
<min_angle>-1.5707963</min_angle>
<max_angle>+1.5707963</max_angle>
</horizontal>
</scan>
<range>
<min>0.1</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>scan</topicName>
<frameName>hokuyo_link</frameName>
</plugin>
</sensor>
</gazebo>
- usb camera
<gazebo reference="camera_link">
<sensor type="camera" name="camera">
<update_rate>50</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>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>camera</cameraName>
<imageTopicName>image</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>
- IMU
<gazebo>
<plugin name="imu_plugin" filename="libgazebo_ros_imu.so">
<alwaysOn>true</alwaysOn>
<bodyName>base_footprint</bodyName>
<topicName>imu</topicName>
<serviceName>imu_service</serviceName>
<gaussianNoise>0.0</gaussianNoise>
<updateRate>20.0</updateRate>
</plugin>
</gazebo>
<gazebo reference="imu_link">
<gravity>true</gravity>
<sensor name="imu_sensor" type="imu">
<pose>0 0 0 0 0 0</pose>
<always_on>true</always_on>
<update_rate>100</update_rate>
<visualize>true</visualize>
<topic>__default_topic__</topic>
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
<topicName>imu/data</topicName>
<bodyName>imu_link</bodyName>
<updateRateHZ>10.0</updateRateHZ>
<gaussianNoise>0.0</gaussianNoise>
<xyzOffset>0 0 0</xyzOffset>
<rpyOffset>0 0 0</rpyOffset>
<frameName>imu_link</frameName>
</plugin>
</sensor>
</gazebo>
- RGBD camera
<gazebo reference="kinect_link">
<sensor type="depth" name="openni_camera">
<always_on>1</always_on>
<visualize>true</visualize>
<camera>
<horizontal_fov>2.8</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>B8G8R8</format>
</image>
<depth_camera>
</depth_camera>
<clip>
<near>0.01</near>
<far>100</far>
</clip>
</camera>
<plugin name="onepni_camera_controller" filename="libgazebo_ros_openni_kinect.so">
<alwaysOn>true</alwaysOn>
<updateRate>10.0</updateRate>
<cameraName>under/camera</cameraName>
<frameName>kinect_pointcloud_link</frameName>
<imageTopicName>rgb/image_raw</imageTopicName>
<depthImageTopicName>depth/image_raw</depthImageTopicName>
<pointCloudTopicName>depth/points</pointCloudTopicName>
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
<pointCloudCutoff>0.4</pointCloudCutoff>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
<CxPrime>0.0</CxPrime>
<Cx>0.0</Cx>
<Cy>0.0</Cy>
<focalLength>0.0</focalLength>
</plugin>
</sensor>
</gazebo>
-
velodyne laser
16线:/opt/ros/kinetic/share/velodyne_description/urdf/VLP-16.urdf.xacro
32线:/opt/ros/kinetic/share/velodyne_description/urdf/HDL-32E.urdf.xacro -
GPS
<gazebo>
<plugin name="gps_controller" filename="libhector_gazebo_ros_gps.so">
<alwayson>true</alwayson>
<updaterate>10.0</updaterate>
<bodyname>base_link</bodyname>
<topicname>/fix</topicname>
<velocitytopicname>/fix_velocity</velocitytopicname>
<drift>5.0 5.0 5.0</drift>
<gaussiannoise>0.1 0.1 0.1</gaussiannoise>
<velocitydrift>0 0 0</velocitydrift>
<velocitygaussiannoise>0.1 0.1 0.1</velocitygaussiannoise>
</plugin>
</gazebo>
https://answers.ros.org/question/258307/gazebo-simulation-gps-fix/
- video 视频
<gazebo reference="video_link">
<visual>
<plugin name="display_video_controller" filename="libgazebo_ros_video.so">
<topicName>image</topicName>
<height>120</height>
<width>160</width>
</plugin>
</visual>
</gazebo>
- 立体相机(多机位)
<gazebo reference="left_camera_frame">
<sensor type="multicamera" name="stereo_camera">
<update_rate>30.0</update_rate>
<camera name="left">
<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>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<camera name="right">
<pose>0 -0.07 0 0 0 0</pose>
<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>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="stereo_camera_controller" filename="libgazebo_ros_multicamera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>multisense_sl/camera</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>left_camera_optical_frame</frameName>
<!--<rightFrameName>right_camera_optical_frame</rightFrameName>-->
<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>
- 碰撞传感器
<gazebo reference="bumper_link">
<sensor name="contacts" type="contact">
<contact>
<collision>base_footprint_fixed_joint_lump__base_collision_collision_1</collision>
</contact>
<plugin name="gazebo_ros_bumper_controller" filename="libgazebo_ros_bumper.so">
<always_on>true</always_on>
<robotNamespace>/robot</robotNamespace>
<bumperTopicName>bumper_states</bumperTopicName>
<frameName>bumper</frameName>
<visualize>true</visualize>
<update_rate>50.0</update_rate>
</plugin>
</sensor>
<material>Gazebo/Red</material>
<mu1>0.1</mu1>
<mu2>0.1</mu2>
<gravity>true</gravity>
<selfCollide>false</selfCollide>
</gazebo>