【RVIZ+GAZEBO+URDF】 --- 1-3. 为机器人添加彩色相机

前言

沿用上一章的gazebo中的机器人,为机器人使用摄像头插件。大概流程和move.xacro步骤一致,略。

  1. 延用工作空间test2_ws;
  2. 功能包demo4_urdf_gazebo存放代码;
  3. laser的xacro代码放在demo4_urdf_gazebo/urdf/xacro/gazebo/camera.xacro;
  4. 最后综合launch文件demo4_urdf_gazebo/launch/all.launch.

先写camera.xacro文件,然后在综合xacro文件中加入camera文件即可。

camera.xacro文件详解

  • 摄像头插件节点的命名空间
<sensor type="camera" name="camera_node">
  • 对应base中摄像头的link
<gazebo reference="camera">
  • 话题名,接命名空间构成话题/camera/image_raw。图像信息被发布于此。
<imageTopicName>image_raw</imageTopicName>

效果展示

gazebo中没有太大变化,主要是rviz中。

rviz

需要小小配置一下,加入camera,然后选中订阅话题/camera/imageraw,可以驱动小车,可以看到图像随之变动。

laser

camera.xacro源码

<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro">
  <!-- base's link -->
  <gazebo reference="camera">
    <!--  camara namespace-->
    <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>
      <!-- core plugin -->
      <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
    点赞
  • 1
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值