修正帧头为PI/4<--->7PI/4

This commit is contained in:
NimblKun 2022-03-29 09:42:51 +08:00
parent 8b8c5fc4dd
commit 5a82ad239b

View File

@ -1,7 +1,7 @@
#include <ros/ros.h>
#include <sensor_msgs/LaserScan.h>
#include "hins/xingsong_driver.h"
#include <iostream>
using namespace hins;
sensor_msgs::LaserScanPtr ToLaserScan(const ScanData &data, const float& start_angle, const float& end_angle, const std::string& frame_name);
@ -56,8 +56,8 @@ sensor_msgs::LaserScanPtr ToLaserScan(const ScanData &data, const float& start_a
ret->range_min = 0.05;
ret->range_max = 10.0;
ret->angle_min = M_PI/2.0f;
ret->angle_max = 3.0 * M_PI/2.0f;
ret->angle_min = M_PI/4.0f;
ret->angle_max = 7.0 * M_PI/4.0f;
ret->time_increment = 1/20/float(data.distance_data.size()); // 一个周期时间除以扫描点数
@ -71,7 +71,7 @@ sensor_msgs::LaserScanPtr ToLaserScan(const ScanData &data, const float& start_a
float angle = ret->angle_min + i * ret->angle_increment;
float dis = float(data.distance_data[i])/1000.0f;
if(angle < start_angle || angle > end_angle)
ret->ranges[i] = 1024.0;
else