文章结构
- 雷达信息仿真以及显示
- Gazebo仿真雷达
- 配置雷达传感器信息
- xacro文件集成
- 启动仿真环境
- Rviz显示雷达数据
- 摄像头信息仿真以及显示
- Gazebo仿真摄像头
- 新建xacro文件,配置摄像头传感器信息
- xacro文件集成
- 启动仿真环境
- Rviz显示摄像头数据
- kinect信息仿真以及显示
- Gazebo仿真Kinect
- 新建 Xacro 文件,配置 kinetic传感器信息
- xacro文件集成
- 启动仿真环境
- Rviz显示Kinect数据
- kinect点云数据显示
雷达信息仿真以及显示
通过 Gazebo 模拟激光雷达传感器,并在 Rviz 中显示激光数据。
实现流程:
-
已经创建完毕的机器人模型,编写一个单独的 xacro 文件,为机器人模型添加雷达配置;
-
将此文件集成进xacro文件;
-
启动 Gazebo,使用 Rviz 显示雷达信息。
Gazebo仿真雷达
配置雷达传感器信息
<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro"><gazebo reference="laser"><sensor type="ray" name="rplidar"><pose>0 0 0 0 0 0</pose><visualize>true</visualize><update_rate>5.5</update_rate><ray><scan><horizontal><samples>360</samples><resolution>1</resolution><min_angle>-3</min_angle><max_angle>3</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_rplidar" filename="libgazebo_ros_laser.so"><topicName>/scan</topicName><frameName>laser</frameName></plugin></sensor></gazebo>
</robot>
xacro文件集成
<robot name="mycar" xmlns:xacro="http://www.ros.org/wiki/xacro"><xacro:include filename="../head.xacro"/><xacro:include filename="demo05_car_base.urdf.xacro"/><xacro:include filename="demo06_car_camera.urdf.xacro"/><xacro:include filename="demo07_car_laser.urdf.xacro"/><xacro:include filename="../gazebo/move.xacro"/><xacro:include filename="../gazebo/laser.xacro"/>
</robot>
启动仿真环境
Rviz显示雷达数据
先启动 rviz,添加雷达信息显示插件
摄像头信息仿真以及显示
通过 Gazebo 模拟摄像头传感器,并在 Rviz 中显示摄像头数据。
实现流程:
-
已经创建完毕的机器人模型,编写一个单独的 xacro 文件,为机器人模型添加摄像头配置;
-
将此文件集成进xacro文件;
-
启动 Gazebo,使用 Rviz 显示摄像头信息。
Gazebo仿真摄像头
新建xacro文件,配置摄像头传感器信息
<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro"><!-- 被引用的link --><gazebo reference="camera"><!-- 类型设置为 camara --><sensor type="camera" name="camera_node"><update_rate>30.0</update_rate> <!-- 更新频率 --><!-- 摄像头基本信息设置 --><camera name="head"><horizontal_fov>1.3962634</horizontal_fov><image><width>1280</width><height>720</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="gazebo_camera" filename="libgazebo_ros_camera.so"><alwaysOn>true</alwaysOn><updateRate>0.0</updateRate><cameraName>/camera</cameraName><imageTopicName>image_raw</imageTopicName><cameraInfoTopicName>camera_info</cameraInfoTopicName><frameName>camera</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>
xacro文件集成
<robot name="mycar" xmlns:xacro="http://www.ros.org/wiki/xacro"><xacro:include filename="../head.xacro"/><xacro:include filename="demo05_car_base.urdf.xacro"/><xacro:include filename="demo06_car_camera.urdf.xacro"/><xacro:include filename="demo07_car_laser.urdf.xacro"/><xacro:include filename="../gazebo/move.xacro"/><xacro:include filename="../gazebo/laser.xacro"/><xacro:include filename="../gazebo/camera.xacro"/>
</robot>
启动仿真环境
Rviz显示摄像头数据
执行 gazebo 并启动 Rviz,在 Rviz 中添加摄像头组件。
实现效果:
kinect信息仿真以及显示
通过 Gazebo 模拟kinect摄像头,并在 Rviz 中显示kinect摄像头数据。
实现流程:
-
已经创建完毕的机器人模型,编写一个单独的 xacro 文件,为机器人模型添加kinect摄像头配置;
-
将此文件集成进xacro文件;
-
启动 Gazebo,使用 Rviz 显示kinect摄像头信息。
Gazebo仿真Kinect
新建 Xacro 文件,配置 kinetic传感器信息
<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro"><gazebo reference="support"> <!-- reference为kinect link名称 --><sensor type="depth" name="camera"><always_on>true</always_on><update_rate>20.0</update_rate><camera><horizontal_fov>${60.0*PI/180.0}</horizontal_fov><image><format>R8G8B8</format><width>640</width><height>480</height></image><clip><near>0.05</near><far>8.0</far></clip></camera><plugin name="kinect_camera_controller" filename="libgazebo_ros_openni_kinect.so"><cameraName>camera</cameraName><alwaysOn>true</alwaysOn><updateRate>10</updateRate><imageTopicName>rgb/image_raw</imageTopicName><depthImageTopicName>depth/image_raw</depthImageTopicName><pointCloudTopicName>depth/points</pointCloudTopicName><cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName><depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName><frameName>support</frameName><baseline>0.1</baseline><distortion_k1>0.0</distortion_k1><distortion_k2>0.0</distortion_k2><distortion_k3>0.0</distortion_k3><distortion_t1>0.0</distortion_t1><distortion_t2>0.0</distortion_t2><pointCloudCutoff>0.4</pointCloudCutoff></plugin></sensor></gazebo>
</robot>
xacro文件集成
<robot name="mycar" xmlns:xacro="http://www.ros.org/wiki/xacro"><xacro:include filename="../head.xacro"/><xacro:include filename="demo05_car_base.urdf.xacro"/><xacro:include filename="demo06_car_camera.urdf.xacro"/><xacro:include filename="demo07_car_laser.urdf.xacro"/><xacro:include filename="../gazebo/move.xacro"/><xacro:include filename="../gazebo/laser.xacro"/><xacro:include filename="../gazebo/camera.xacro"/><xacro:include filename="../gazebo/kinect.xacro"/>
启动仿真环境
Rviz显示Kinect数据
启动 rviz,添加摄像头组件查看数据
实现效果:
kinect点云数据显示
- 在插件中为kinect设置坐标系,修改配置文件的标签内容:
<frameName>support_depth</frameName>
- 发布新设置的坐标系到kinect连杆的坐标变换关系,在启动rviz的launch中,添加:
<node pkg="tf2_ros" type="static_transform_publisher" name="static_transform_publisher" args="0 0 0 -1.57 0 -1.57 /support /support_depth" />
- 启动rviz并添加组件