综合运动控制:摄像头信息仿真及显示
(1)新建camera.xacro文件并集成到机器人模型的xacro文件中(include)
编写camera.xacro文件,主要需要修改的地方有(类似雷达仿真):
gazebo reference:将该文件作用到小车文件的哪个连杆上,要与摄像头的link name保持一致
frame name:摄像头坐标系名称,同上,与摄像头link name一致
<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>
(2)通过roslaunch命令打开gazebo环境和rivz
gazebo和雷达仿真结果没有区别,现在rviz中添加插件查看摄像头的情况
小车运动时,也可以看到下面摄像头的画面会随之运动
可以通过话题发布命令查看运动是的摄像头画面变化,cmd_vel话题,这里可以tab键自动补齐
rostopic pub -r 10 /cmd_vel geometry_msgs/Twist"linear:
x:1.0
y:2.0
z:0
angular:
x:0
y:0
z:0.5"
这里另外加入了雷达仿真的可视化效果,下面是效果视频
雷达摄像头仿真