1. 程式人生 > >ROS中釋出點雲資訊和里程計訊息

ROS中釋出點雲資訊和里程計訊息

一。ROS使用tf來決定機器人的位置和靜態地圖中的感測器資料,但是tf中沒有機器人的速度資訊,所以導航功能包要求機器人 能夠通過里程計資訊源釋出包含速度資訊的里程計nav_msgs/Odometry 訊息。 本篇將介紹nav_msgs/Odometry訊息,並且通過程式碼實現訊息的釋出,以及tf樹的變換。這裡使用一個簡單的例程,實現 nav_msgs/Odometry訊息的釋出和tf變換,通過偽造的資料,實現機器人圓周運動。

1.1.首先在你得ros工作空間中新建功能包,包含以下庫:

catkin_create_pkg odom_tf_package std_msgs rospy roscpp sensor_msgs tf nav_msgs

1.2.在odom_tf_package/src下建立TF變換的程式碼檔案:

touch odom_tf_node.cpp

原始碼如下:(建議初學者必須認真閱讀程式碼,搞清所釋出的話題上的訊息和訊息型別等)

複製程式碼
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>



int main(int argc, char** argv)
{

    ros::init(argc, argv, "odometry_publisher");
    ros::NodeHandle n;
    ros::Publisher odom_pub 
= n.advertise<nav_msgs::Odometry>("odom", 50); tf::TransformBroadcaster odom_broadcaster; double x = 0.0; double y = 0.0; double th = 0.0; double vx = 0.1; double vy = -0.1; double vth = 0.1; ros::Time current_time, last_time; current_time = ros::Time::now(); last_time
= ros::Time::now(); ros::Rate r(1.0); while(n.ok()) { ros::spinOnce(); // check for incoming messages current_time = ros::Time::now(); //compute odometry in a typical way given the velocities of the robot double dt = (current_time - last_time).toSec(); double delta_x = (vx * cos(th) - vy * sin(th)) * dt; double delta_y = (vx * sin(th) + vy * cos(th)) * dt; double delta_th = vth * dt; x += delta_x; y += delta_y; th += delta_th; //since all odometry is 6DOF we'll need a quaternion created from yaw geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th); //first, we'll publish the transform over tf geometry_msgs::TransformStamped odom_trans; odom_trans.header.stamp = current_time; odom_trans.header.frame_id = "odom"; odom_trans.child_frame_id = "base_link"; odom_trans.transform.translation.x = x; odom_trans.transform.translation.y = y; odom_trans.transform.translation.z = 0.0; odom_trans.transform.rotation = odom_quat; //send the transform odom_broadcaster.sendTransform(odom_trans); //next, we'll publish the odometry message over ROS nav_msgs::Odometry odom; odom.header.stamp = current_time; odom.header.frame_id = "odom"; //set the position odom.pose.pose.position.x = x; odom.pose.pose.position.y = y; odom.pose.pose.position.z = 0.0; odom.pose.pose.orientation = odom_quat; //set the velocity odom.child_frame_id = "base_link"; odom.twist.twist.linear.x = vx; odom.twist.twist.linear.y = vy; odom.twist.twist.angular.z = vth; //publish the message odom_pub.publish(odom); last_time = current_time; r.sleep(); } }
複製程式碼

下面來剖析程式碼進行分析:

    #include <tf/transform_broadcaster.h>
    #include <nav_msgs/Odometry.h>

 我們需要實現“odom”參考系到“base_link”參考系的變換,以及nav_msgs/Odometry訊息的釋出,所以首先需要包含相關的標頭檔案。

      ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("odom", 50);  
      tf::TransformBroadcaster odom_broadcaster;

  定義一個訊息釋出者來發布“odom”訊息,在定義一個tf廣播,來發布tf變換資訊。

      double x = 0.0;
      double y = 0.0;
      double th = 0.0;

 預設機器人的起始位置是odom參考系下的0點。

      double vx = 0.1;
      double vy = -0.1;
      double vth = 0.1;

我們設定機器人的預設前進速度,讓機器人的base_link參考系在odom參考系下以x軸方向0.1m/s,Y軸速度-0.1m/s,角速度0.1rad/s的狀態移動,這種狀態下,可以讓機器人保持圓周運動。

  ros::Rate r(1.0);

使用1Hz的頻率釋出odom訊息,當然,在實際系統中,往往需要更快的速度進行釋出。

複製程式碼
        //compute odometry in a typical way given the velocities of the robot
        double dt = (current_time - last_time).toSec();
        double delta_x = (vx * cos(th) - vy * sin(th)) * dt;
        double delta_y = (vx * sin(th) + vy * cos(th)) * dt;
        double delta_th = vth * dt;
    
        x += delta_x;
        y += delta_y;
        th += delta_th;
複製程式碼

使用我們設定的速度資訊,來計算並更新里程計的資訊,包括單位時間內機器人在x軸、y軸的座標變化和角度的變化。在實際系統中,需要更具里程計的實際資訊進行更新。

       //since all odometry is 6DOF we'll need a quaternion created from yaw
        geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th);

為了相容二維和三維的功能包,讓訊息結構更加通用,里程計的偏航角需要轉換成四元數才能釋出,辛運的是,ROS為我們提供了偏航角與四元數相互轉換的功能。

        //first, we'll publish the transform over tf
        geometry_msgs::TransformStamped odom_trans;
        odom_trans.header.stamp = current_time;
        odom_trans.header.frame_id = "odom";
        odom_trans.child_frame_id = "base_link";

 建立一個tf釋出需要使用的TransformStamped型別訊息,然後根據訊息結構填充當前的時間戳、參考系id、子參考系id,注意兩個參考系的id必須要是“odom”和“base_link”。

        odom_trans.transform.translation.x = x;
        odom_trans.transform.translation.y = y;
        odom_trans.transform.translation.z = 0.0;
        odom_trans.transform.rotation = odom_quat;

 填充里程計資訊,然後釋出tf變換的訊息。

        //next, we'll publish the odometry message over ROS
        nav_msgs::Odometry odom;
        odom.header.stamp = current_time;

我們還要釋出nav_msgs/Odometry訊息,讓導航包獲取機器人的速度。建立訊息變數,然後填充時間戳。

複製程式碼
        //set the position
        odom.pose.pose.position.x = x;
        odom.pose.pose.position.y = y;
        odom.pose.pose.position.z = 0.0;
        odom.pose.pose.orientation = odom_quat;
        //set the velocity
        odom.child_frame_id = "base_link";
        odom.twist.twist.linear.x = vx;
        odom.twist.twist.linear.y = vy;
        odom.twist.twist.angular.z = vth;
複製程式碼

  填充機器人的位置、速度,然後釋出訊息。注意,我們釋出的是機器人本體的資訊,所以參考系需要填"base_link"。

1.3.編譯原始碼:在odom_tf_package/CMakeLists.txt新增編譯選項:

add_executable(odom_tf_node src/odom_tf_node.cpp)
target_link_libraries(odom_tf_node ${catkin_LIBRARIES}

返回到你的工作空間的頂層目錄下:

catkin_make 

二。  在導航過程中,感測器的資訊至關重要,這些感測器可以是鐳射雷達、攝像機、聲納、紅外線、碰撞開關,但是歸根結底,導航功能包要求機器人必須釋出sensor_msgs/LaserScan或sensor_msgs/PointCloud格式的感測器資訊,本篇將詳細介紹如何使用程式碼釋出所需要的訊息。無論是 sensor_msgs/LaserScan,還是sensor_msgs/PointCloud ,都和ROS中tf幀資訊等時間相關的訊息一樣,帶標準格式的頭資訊。

複製程式碼
    #Standard metadata for higher-level flow data types
    #sequence ID: consecutively increasing ID 
    uint32 seq    
    #Two-integer timestamp that is expressed as:
    # * stamp.secs: seconds (stamp_secs) since epoch
    # * stamp.nsecs: nanoseconds since stamp_secs
    # time-handling sugar is provided by the client library
    time stamp     
    #Frame this data is associated with
    # 0: no frame
    # 1: global frame
    string frame_id
複製程式碼

以上是標準頭資訊的主要部分。seq是訊息的順序標識,不需要手動設定,釋出節點在釋出訊息時,會自動累加。stamp 是訊息中與資料相關聯的時間戳,例如鐳射資料中,時間戳對應鐳射資料的採集時間點。frame_id 是訊息中與資料相關聯的參考系id,例如在在鐳射資料中,frame_id對應鐳射資料採集的參考系。

2.1.如何釋出點雲資料

點雲訊息的結構

複製程式碼
    #This message holds a collection of 3d points, plus optional additional information about each point.   
    #Each Point32 should be interpreted as a 3d point in the frame given in the header          
   
    Header header     
    geometry_msgs/Point32[] points  #Array of 3d points  
    ChannelFloat32[] channels       #Each channel should have the same number of elements as points array, and the data in each channel should correspond 1:1 with each point
複製程式碼

如上所示,點雲訊息的結構支援儲存三維環境的點陣列,而且channels引數中,可以設定這些點雲相關的資料,例如可以設定一個強度通道,儲存每個點的資料強度,還可以設定一個係數通道,儲存每個點的反射係數,等等。

2.2.通過程式碼釋出點雲資料

.在odom_tf_package/src下建立TF變換的程式碼檔案:

touch point_kinect_node.cpp

原始碼如下:

複製程式碼
#include "ros/ros.h"
#include <sensor_msgs/PointCloud.h>

int main(int argc, char** argv)
{
    ros::init(argc, argv, "point_cloud_publisher");
    ros::NodeHandle n;
    ros::Publisher cloud_pub = n.advertise<sensor_msgs::PointCloud>("cloud", 50);
    unsigned int num_points = 100;
    int count = 0;
    ros::Rate r(1.0);
    while(n.ok())
    {

        sensor_msgs::PointCloud cloud;
        cloud.header.stamp = ros::Time::now();
        cloud.header.frame_id = "sensor_frame";

        cloud.points.resize(num_points);


        //we'll also add an intensity channel to the cloud
        cloud.channels.resize(1);
        cloud.channels[0].name = "intensities";
        cloud.channels[0].values.resize(num_points);

        //generate some fake data for our point cloud

        for(unsigned int i = 0; i < num_points; ++i)
        {
            cloud.points[i].x = 1 + count;
            cloud.points[i].y = 2 + count;
            cloud.points[i].z = 3 + count;
            cloud.channels[0].values[i] = 100 + count;
        }

        cloud_pub.publish(cloud);

        ++count;
        r.sleep();
    }

}
複製程式碼

分解程式碼來分析:

#include <sensor_msgs/PointCloud.h>

 首先也是要包含sensor_msgs/PointCloud訊息結構。

    ros::Publisher cloud_pub = n.advertise<sensor_msgs::PointCloud>("cloud", 50);

定義一個釋出點雲訊息的釋出者。

        sensor_msgs::PointCloud cloud;
        cloud.header.stamp = ros::Time::now();
        cloud.header.frame_id = "sensor_frame";

 為點雲訊息填充頭資訊,包括時間戳和相關的參考系id。

    cloud.points.resize(num_points);

設定儲存點雲資料的空間大小。

        //we'll also add an intensity channel to the cloud
        cloud.channels.resize(1);
        cloud.channels[0].name = "intensities";
        cloud.channels[0].values.resize(num_points);

設定一個名為“intensity“的強度通道,並且設定儲存每個點強度資訊的空間大小。

        //generate some fake data for our point cloud
        for(unsigned int i = 0; i < num_points; ++i){
          cloud.points[i].x = 1 + count;
          cloud.points[i].y = 2 + count;
          cloud.points[i].z = 3 + count;
          cloud.channels[0].values[i] = 100 + count;   

 將我們偽造的資料填充到點雲訊息結構當中。

   cloud_pub.publish(cloud);

 最後,釋出點雲資料。

2.3.編譯原始碼:在odom_tf_package/CMakeLists.txt新增編譯選項:

add_executable(point_kinect_node src/point_kinect_node.cpp)
target_link_libraries(point_kinect_node ${catkin_LIBRARIES}

返回到你的工作空間的頂層目錄下:

catkin_make

三:測試程式碼:

roscore
rosrun odom_tf_package odom_tf_node
rosrun odom_tf_package point_kinect_node
rviz

3.1.rviz檢視如下:tf變換和機器人移動資訊.

3.2.檢視釋出的點雲資料。

rostopic echo /cloud