Ros 消息结构1
1、ROS的消息頭信息
????
#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、激光消息的結構
??????針對激光雷達,ROS在sensor_msgs?包中定義了專用了數據結構來存儲激光消息的相關信息,成為LaserScan。LaserScan消息的格式化定義,為虛擬的激光雷達數據采集提供了方便,在我們討論如何使用他之前,來看看該消息的結構是什么樣的:
# # Laser scans angles are measured counter clockwise, with 0 facing forward # (along the x-axis) of the device frame #Header header float32 angle_min # start angle of the scan [rad] float32 angle_max # end angle of the scan [rad] float32 angle_increment # angular distance between measurements [rad] float32 time_increment # time between measurements [seconds] float32 scan_time # time between scans [seconds] float32 range_min # minimum range value [m] float32 range_max # maximum range value [m] float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded) float32[] intensities # intensity data [device-specific units]????? 備注中已經詳細介紹了每個參數的意義。
2.2、通過代碼發布LaserScan消息
????使用ROS發布LaserScan格式的激光消息非常簡潔,下邊是一個簡單的例程:
#include <ros/ros.h> #include <sensor_msgs/LaserScan.h>int main(int argc, char** argv){ros::init(argc, argv, "laser_scan_publisher");ros::NodeHandle n;ros::Publisher scan_pub = n.advertise<sensor_msgs::LaserScan>("scan", 50);unsigned int num_readings = 100;double laser_frequency = 40;double ranges[num_readings];double intensities[num_readings];int count = 0;ros::Rate r(1.0);while(n.ok()){//generate some fake data for our laser scanfor(unsigned int i = 0; i < num_readings; ++i){ranges[i] = count;intensities[i] = 100 + count;}ros::Time scan_time = ros::Time::now();//populate the LaserScan messagesensor_msgs::LaserScan scan;scan.header.stamp = scan_time;scan.header.frame_id = "laser_frame";scan.angle_min = -1.57;scan.angle_max = 1.57;scan.angle_increment = 3.14 / num_readings;scan.time_increment = (1 / laser_frequency) / (num_readings);scan.range_min = 0.0;scan.range_max = 100.0;scan.ranges.resize(num_readings);scan.intensities.resize(num_readings);for(unsigned int i = 0; i < num_readings; ++i){scan.ranges[i] = ranges[i];scan.intensities[i] = intensities[i];}scan_pub.publish(scan);++count;r.sleep();} }
????我們將代碼分解以便于分析:
#include <sensor_msgs/LaserScan.h>????首先我們需要先包含Laserscan的數據結構。
ros::Publisher scan_pub = n.advertise<sensor_msgs::LaserScan>("scan", 50);????創建一個發布者,以便于后邊發布針對scan主題的Laserscan消息。
unsigned int num_readings = 100;double laser_frequency = 40;double ranges[num_readings];double intensities[num_readings];int count = 0;ros::Rate r(1.0);while(n.ok()){//generate some fake data for our laser scanfor(unsigned int i = 0; i < num_readings; ++i){ranges[i] = count;intensities[i] = 100 + count;}ros::Time scan_time = ros::Time::now();????這里的例程中我們虛擬一些激光雷達的數據,如果使用真是的激光雷達,這部分數據需要從驅動中獲取。
//populate the LaserScan messagesensor_msgs::LaserScan scan;scan.header.stamp = scan_time;scan.header.frame_id = "laser_frame";scan.angle_min = -1.57;scan.angle_max = 1.57;scan.angle_increment = 3.14 / num_readings;scan.time_increment = (1 / laser_frequency) / (num_readings);scan.range_min = 0.0;scan.range_max = 100.0;scan.ranges.resize(num_readings);scan.intensities.resize(num_readings);for(unsigned int i = 0; i < num_readings; ++i){scan.ranges[i] = ranges[i];scan.intensities[i] = intensities[i];}????創建scan_msgs::LaserScan數據類型的變量scan,把我們之前偽造的數據填入格式化的消息結構中。
scan_pub.publish(scan);? ??數據填充完畢后,通過前邊定義的發布者,將數據發布。
3.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 headerHeader headergeometry_msgs/Point32[] points #Array of 3d pointsChannelFloat32[] 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參數中,可以設置這些點云相關的數據,例如可以設置一個強度通道,存儲每個點的數據強度,還可以設置一個系數通道,存儲每個點的反射系數,等等。
3.2、通過代碼發布點云數據
???? ROS發布點云數據同樣簡潔:
#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 cloudcloud.channels.resize(1);cloud.channels[0].name = "intensities";cloud.channels[0].values.resize(num_points);//generate some fake data for our point cloudfor(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 cloudfor(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);? ? ? 最后,發布點云數據。
總結
- 上一篇: 上线7年 腾讯看点快报App宣布停运
- 下一篇: 《生化4重制》王阿姨要更换动捕演员:华裔