ROS笔记之Gazebo机器人仿真(六)——机器人模型插件添加
1.引言
这章里我们将结束如何给机器人模型添加插件。
2.传感器插件
2.1激光雷达插件
(1)在urdf文件夹下的smartcar.urdf中添加:
<gazebo reference="sensor_link">
<sensor type="ray" name="head_hokuyo_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>40</update_rate>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>1</resolution>
<min_angle>-1.570796</min_angle>
<max_angle>1.570796</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</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>/laser/scan</topicName>
<frameName>base_link</frameName>
</plugin>
</sensor>
</gazebo>
这里对常需要修改的部分代码进行说明:
<gazebo reference="sensor_link">
表示激光雷达的元件名称为"sensor_link"
<topicName>/laser/scan</topicName>
表示激光雷达数据的topic名称为“/laser/scan”
<frameName>base_link</frameName>
表示基架为“base_link”
(2)在两个终端分别输入指令:
roslaunch smartcar gazebo.launch
roslaunch smartcar display.launch
(3)在Rviz界面中添加显示激光雷达
(4)可以看到添加的激光雷达插件产生的“/laser/scan”的Topic
2.2 RGB-D相机插件
我们可以将“sensor_link”定义为激光雷达也可以添加相应的插件将其定义为 RGB-D相机。
(1)在urdf文件夹下的smartcar.urdf中添加:
<gazebo reference="sensor_link">
<sensor type="depth" name="camera1">
<always_on>1</always_on>
<visualize>true</visualize>
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<depth_camera>
</depth_camera>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_openni_kinect.so">
<alwaysOn>true</alwaysOn>
<updateRate>5</updateRate>
<cameraName>kinect2</cameraName>
<frameName>base_link</frameName>
<imageTopicName>qhd/image_color_rect</imageTopicName>
<depthImageTopicName>qhd/image_depth_rect</depthImageTopicName>
<pointCloudTopicName>depth/points</pointCloudTopicName>
<cameraInfoTopicName>qhd/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>
<hackBaseline>0</hackBaseline>
</plugin>
</sensor>
</gazebo>
(2)在两个终端分别输入指令:
roslaunch smartcar gazebo.launch
roslaunch smartcar display.launch
(3)在Rviz界面添加相应Topic就能看到深度图像和彩色图像
3.运动控制插件
为了能让机器人运动起来,我们还需要添加滑动转向驱动:
<gazebo>
<plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
<alwaysOn>true</alwaysOn>
<updateRate>5</updateRate>
<leftFrontJoint>wheel1_joint</leftFrontJoint>
<rightFrontJoint>wheel3_joint</rightFrontJoint>
<leftRearJoint>wheel2_joint</leftRearJoint>
<rightRearJoint>wheel4_joint</rightRearJoint>
<wheelSeparation>0.060</wheelSeparation>
<wheelDiameter>0.040</wheelDiameter>
<torque>20</torque>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<robotBaseFrame>base_link</robotBaseFrame>
<broadcastTF>1</broadcastTF>
</plugin>
</gazebo>
想要添加更多Gazebo插件,可以看这里。