目录
- 目录
- ROS 传感器消息
- ROS 传感器消息之Laserscan
- 消息定义
- 测试代码
- ROS 传感器消息之PointCloud
- 消息定义
- 测试代码
- ROS 传感器消息之Laserscan
- 小结
- Reference
ROS 传感器消息
在使用ROS各个传感器消息之前,弄清楚各个传感器在ROS是如何表示的显得极为重要。特别是,Laserscan, PointCloud等用了很久之后,感觉已经很熟悉了,但是一些细节行的东西一直没有深究,并且对某些参数难以形成直觉上的认识,很大程度上影响了在与其他算法或者硬件衔接时的问题。这里,我单独的将Laserscan,PointCloud发布在rviz中,通过修改不同的ROS消息参数,直观的观察其在参数的作用。整个工程代码可以在此处下载:https://download.csdn.net/download/ziqian0512/10289936。
ROS 传感器消息之Laserscan
消息定义
首先,查看一下sensor_msgs/LaserScan.msg的定义,见ros.org/LaserScan.“`
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]
在消息中需要特别说明的主要是ranges和intensities,ranges表示在某一个角度时,扫描到物体离自己的距离,这很容易理解。intensities则表示测量的强度,也就是激光所反射的亮度,通常来说,值越大,光反射越亮。也就可以用intensities做一些假设,推荐扫描到物体的材料。比如,Hokyuo Laser scanner就提供了反射的所有强度,而 Sick S300则只检测是否由反光带。
测试代码
以下为测试Laserscan源码,需要特别关注的num_readings(点数),ranges(距离),intensities(强度)参数在调节过程中,rviz中Laserscan的变化。 编译以下代码后,还需要选择sensor_frame坐标系,和消息/scan。效果图如下: 代码:
#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 = 10;
ros::Rate r(1.0);
while(n.ok()){
//generate some fake data for our laser scan
for(unsigned int i = 0; i < num_readings; ++i){
ranges[i] = count;
intensities[i] = 10*i;
}
ros::Time scan_time = ros::Time::now();
//populate the LaserScan message
sensor_msgs::LaserScan scan;
scan.header.stamp = scan_time;
scan.header.frame_id = "sensor_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;
ROS_WARN_STREAM("count"<<count);
r.sleep();
}
}
ROS 传感器消息之PointCloud
消息定义
PointCloud 描述如下:
Header header
geometry_msgs/Point32[] points # Array of 3d points
ChannelFloat32[] channels # channel name, value
channels可以进一步解释为:
# "rgb" - For point clouds produced by color stereo cameras. uint8 (R,G,B) values packed into the least significant 24 bits,in order.
# "intensity" - laser or pixel intensity.
# The channel name should give the semantics of the channel (e.g. "intensity" instead of "value").
string name
# The values array should be 1-1 with the elements of the associated PointCloud.
float32[] values
name表示不同的表示方式,可以是像素值,亮度等。values则是典型的依赖于传感器的亮度值返回,表示测量的质量,可以是灰度图像的灰度值,也可以是类似laserscan的强度。
测试代码
在以下代码中,重点需要调节num_points(点数),channels(设置通道,以及强度),points(位置)参数来观察PointCloud的变化。编译以下代码后,还需要选择sensor_frame坐标系,和消息/cloud。效果图如下: 代码
#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 = 2000;
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 + i/100;
cloud.points[i].y = 1;
cloud.points[i].z = 1;
cloud.channels[0].values[i] = 100 * i;
}
cloud_pub.publish(cloud);
// ++count;
r.sleep();
}
}
小结
详细的介绍需要已经有很多了,自己动手调试并观察rviz中传感器数据的变化可以加强对使用传感器以及研究其算法增加直观的体验。目的是为了自己更加方便的查询和使用。
Reference