一、原因
- 由于激光雷达是360度的,在建图导航时影响很大,所以选择对激光数据进行角度切割。
- Rplidar A2M8的数据格式和其他的A2的数据格式不一样,参考一些关于A2的教程时报错,所以只对角度进行简单的处理。
- 关于激光的坐标系,是使用TF变换纠正的,或者将激光雷达反向安装。
二、修改源代码
node.cpp中 找到publish_scan
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)
{
static int scan_count = 0;
sensor_msgs::LaserScan scan_msg;
scan_msg.header.stamp = start;
scan_msg.header.frame_id = frame_id;
scan_count++;
bool reversed = (angle_max > angle_min);
if ( reversed ) {
scan_msg.angle_min = M_PI - angle_max;
scan_msg.angle_max = M_PI - angle_min;
} else {
scan_msg.angle_min = M_PI - angle_min;
scan_msg.angle_max = M_PI - angle_max;
}
scan_m