Ros用LaserScan封装环境深度信息。激达雷达、深度摄像头用它定义发出的topic。
$ rosmsg show sensor_msgs/LaserScan std_msgs/Header header uint32 seq time stamp string frame_id float32 angle_min float32 angle_max float32 angle_increment float32 time_increment float32 scan_time float32 range_min float32 range_max float32[] ranges float32[] intensities
注:表中node_count表示这一帧包含的扫描点数目。
字段 | 单位 | 注释 | 思岚RPLIDAR A1M8 |
angle_min | 弧度 | 可检测范围的起始角度 | DEG2RAD(-179) |
angle_max | 弧度 | 可检测范围的终止角度,与angle_min组成传感器的FOV(视场角) | DEG2RAD(180) |
angle_increment | 弧度 | 这一帧中相邻扫描点之间的夹角。一帧中所有扫描点间用同一步长 | (angle_max - angle_min) / (node_count-1) |
time_increment | 秒 | 这一帧中相邻扫描点之间的时间步长。当传感器处于相对运动状态时进行补偿使用 | scan_time / (node_count-1) |
scan_time | 秒 | 采集这一帧耗费的时间 | |
range_min | 米 | 最近可检测深度的阀值 | 0.15 |
range_max | 米 | 最远可检测深度的阀值 | 12 |
ranges | 米 | 存储这一帧深度数据的数组 |
一、示例:思岚RPLIDAR A1M8如何生成LaserScan
/src/node.cpp void publish_scan(ros::Publisher *pub, rplidar_response_measurement_node_hq_t *nodes, size_t node_count, ros::Time start, double scan_time, bool inverted, float angle_min, float angle_max, float max_distance, std::string frame_id) { // node_count表示这一帧包含的扫描点数目。值720,物理意义是每隔0.5度存在个扫描点。 static int scan_count = 0; sensor_msgs::LaserScan scan_msg; scan_msg.header.stamp = start; scan_msg.header.frame_id = frame_id; scan_count++; // angle_min = DEG2RAD(0.0f) <= 0 // float angle_max = DEG2RAD(359.0f) <= 6.26573 bool reversed = (angle_max > angle_min); if ( reversed ) { scan_msg.angle_min = M_PI - angle_max; scan_msg.angle_max = M_PI - angle_min; // [angle_min, angle_max]换成角度相当于[-179, 180] } else { ... } scan_msg.angle_increment = (scan_msg.angle_max - scan_msg.angle_min) / (double)(node_count-1); scan_msg.scan_time = scan_time; scan_msg.time_increment = scan_time / (double)(node_count-1); scan_msg.range_min = 0.15; // A1M8最小测距15cm // A1M8最大测距和工作模式有关。工作在性能优先(Boost)模式时,最大测距12米 scan_msg.range_max = max_distance; // 12.0 scan_msg.intensities.resize(node_count); scan_msg.ranges.resize(node_count); bool reverse_data = (!inverted && reversed) || (inverted && !reversed); if (!reverse_data) { ... } else { for (size_t i = 0; i < node_count; i++) { // 公式dist_mm_q2/4.0f/1000算出该角度上障碍物距离。单位:米 float read_value = (float)nodes[i].dist_mm_q2/4.0f/1000; if (read_value == 0.0) { // read_value = 0表示在range_max(12)米内该角度没障碍物 scan_msg.ranges[node_count-1-i] = std::numeric_limits::infinity(); } else scan_msg.ranges[node_count-1-i] = read_value; scan_msg.intensities[node_count-1-i] = (float) (nodes[i].quality >> 2); } } pub->publish(scan_msg); }
为直观理解,让看下ranges中720个扫描点在直角坐标系的分布情况。红色表示该角度对应的扫描点深度值不是0,即存在障碍物。注意,图1是ranges中扫描点顺序,不是publish_scan中参数nodes中扫描点的顺序,reverse_data=true时,它们是相反。

A1M8在LaserScan报告的视场角是[-179, 180],因而ranges[0]存储的是-179度时的深度值。通过逆时针旋转,一直到180度,即ranges[719]存储的是180度时的深度值。也就是说,第3象限存储ranges最前面的1/4扫描点,第4象限是(1/4, 1/2),第1象限是(1/2, 3/4),第2象限则是最后的1/4。