【RVIZ+GAZEBO+URDF】 — 1-4.添加深度相机kinect,点云数据

  • Post author:
  • Post category:其他




前言

沿用上一章的gazebo中的机器人,为机器人使用深度摄像头插件。大概流程和move.xacro步骤一致,略。既可以查看彩色图像,深度图像还有点云信息.

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

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

注意:这里偷懒将之前激光雷达的支架作为深度相机的载体,因此实际上的kinect在这里具体化为support



kincet.xacro文件详解

  • 摄像头插件节点的命名空间
 <sensor type="depth" name="camera">
  • 对应base中的support
<gazebo reference="name of kinect link ">
...
<frameName>name of kinect link</frameName>



效果展示

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



rviz



1. 彩色图像

配置一下:加入camera,然后选中订阅话题(左侧image_topic)/camera/rgb/image_raw,可以驱动小车,可以看到彩色图像随之变动。

彩色图像



2. 深度图像

配置一下:加入camera,然后选中订阅话题(左侧image_topic)/camera/depth/image_raw,可以驱动小车,可以看到彩色图像随之变动。

深度图像



3. 点云pointcloud2

配置一下:加入PointCloud2,然后选中订阅话题(左侧image_topic)/camera/depth/points,可以驱动小车,可以看到d点云图像随之变动。

点云

此时会发现图像不在正前方,原因是kinect和点云没有共用坐标系,解决办法:

1.在插件kinect.xacro中为kinect设置坐标系,修改配置文件的标签内容:

<frameName>support_depth</frameName>

2.发布新设置的坐标系到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" />

再次打开即可,效果如下

矫正后

方向正确,OK了.



kinnect.xacro源码

<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro">
    <!-- <gazebo reference="name of kinect link ">   -->
    <gazebo reference="support">
      <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_depth</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>



rviz.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 -->
    <node pkg="rviz" type="rviz" name="rviz" args="-d $(find demo4_urdf_gazebo)/config/myrviz.rviz"   />

    <!-- 关节以及机器人状态发布节点 -->
    <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
</launch>



版权声明:本文为Eric_Sober原创文章,遵循 CC 4.0 BY-SA 版权协议,转载请附上原文出处链接和本声明。