通过 Gazebo 模拟激光雷达传感器,并在 Rviz 中显示激光数据。
实现流程:
已经创建完毕的机器人模型,编写一个单独的 xacro 文件,为机器人模型添加雷达配置;
将此文件集成进xacro文件;
启动 Gazebo,使用 Rviz 显示雷达信息。
<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 0pose>
<visualize>truevisualize>
<update_rate>5.5update_rate>
<ray>
<scan>
<horizontal>
<samples>360samples>
<resolution>1resolution>
<min_angle>-3min_angle>
<max_angle>3max_angle>
horizontal>
scan>
<range>
<min>0.10min>
<max>30.0max>
<resolution>0.01resolution>
range>
<noise>
<type>gaussiantype>
<mean>0.0mean>
<stddev>0.01stddev>
noise>
ray>
<plugin name="gazebo_rplidar" filename="libgazebo_ros_laser.so">
<topicName>/scantopicName>
<frameName>laserframeName>
plugin>
sensor>
gazebo>
robot>
<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,添加雷达信息显示插件

通过 Gazebo 模拟摄像头传感器,并在 Rviz 中显示摄像头数据。
实现流程:
已经创建完毕的机器人模型,编写一个单独的 xacro 文件,为机器人模型添加摄像头配置;
将此文件集成进xacro文件;
启动 Gazebo,使用 Rviz 显示摄像头信息。
<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro">
<gazebo reference="camera">
<sensor type="camera" name="camera_node">
<update_rate>30.0update_rate>
<camera name="head">
<horizontal_fov>1.3962634horizontal_fov>
<image>
<width>1280width>
<height>720height>
<format>R8G8B8format>
image>
<clip>
<near>0.02near>
<far>300far>
clip>
<noise>
<type>gaussiantype>
<mean>0.0mean>
<stddev>0.007stddev>
noise>
camera>
<plugin name="gazebo_camera" filename="libgazebo_ros_camera.so">
<alwaysOn>truealwaysOn>
<updateRate>0.0updateRate>
<cameraName>/cameracameraName>
<imageTopicName>image_rawimageTopicName>
<cameraInfoTopicName>camera_infocameraInfoTopicName>
<frameName>cameraframeName>
<hackBaseline>0.07hackBaseline>
<distortionK1>0.0distortionK1>
<distortionK2>0.0distortionK2>
<distortionK3>0.0distortionK3>
<distortionT1>0.0distortionT1>
<distortionT2>0.0distortionT2>
plugin>
sensor>
gazebo>
robot>
<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>
执行 gazebo 并启动 Rviz,在 Rviz 中添加摄像头组件。

实现效果:

通过 Gazebo 模拟kinect摄像头,并在 Rviz 中显示kinect摄像头数据。
实现流程:
已经创建完毕的机器人模型,编写一个单独的 xacro 文件,为机器人模型添加kinect摄像头配置;
将此文件集成进xacro文件;
启动 Gazebo,使用 Rviz 显示kinect摄像头信息。
<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro">
<gazebo reference="support">
<sensor type="depth" name="camera">
<always_on>truealways_on>
<update_rate>20.0update_rate>
<camera>
<horizontal_fov>${60.0*PI/180.0}horizontal_fov>
<image>
<format>R8G8B8format>
<width>640width>
<height>480height>
image>
<clip>
<near>0.05near>
<far>8.0far>
clip>
camera>
<plugin name="kinect_camera_controller" filename="libgazebo_ros_openni_kinect.so">
<cameraName>cameracameraName>
<alwaysOn>truealwaysOn>
<updateRate>10updateRate>
<imageTopicName>rgb/image_rawimageTopicName>
<depthImageTopicName>depth/image_rawdepthImageTopicName>
<pointCloudTopicName>depth/pointspointCloudTopicName>
<cameraInfoTopicName>rgb/camera_infocameraInfoTopicName>
<depthImageCameraInfoTopicName>depth/camera_infodepthImageCameraInfoTopicName>
<frameName>supportframeName>
<baseline>0.1baseline>
<distortion_k1>0.0distortion_k1>
<distortion_k2>0.0distortion_k2>
<distortion_k3>0.0distortion_k3>
<distortion_t1>0.0distortion_t1>
<distortion_t2>0.0distortion_t2>
<pointCloudCutoff>0.4pointCloudCutoff>
plugin>
sensor>
gazebo>
robot>
<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,添加摄像头组件查看数据

实现效果:

<frameName>support_depthframeName>
<node pkg="tf2_ros" type="static_transform_publisher" name="static_transform_publisher" args="0 0 0 -1.57 0 -1.57 /support /support_depth" />
