1 #include <sensor_msgs/PointCloud2.h>
4 #include "pf_driver/PFR2300Header.h"
8 const std::string& scan_topic,
const std::string& frame_id,
9 const uint16_t num_layers,
const std::string& part)
15 p_nh.
getParam(
"correction_params", angles_param);
19 for (
size_t i = 0; i < angles_param.
size(); i++)
21 angles_[i] = angles_param[i][
"ang"];
22 auto coeff_param = angles_param[i][
"coeff"];
23 std::vector<double> coeffs;
24 for (
size_t j = 0; j < coeff_param.size(); j++)
26 coeffs.push_back(coeff_param[j]);
32 for (
int i = 0; i < angles_param.
size(); i++)
34 std::string topic = scan_topic +
"_" + std::to_string(i + 1);
35 std::string
id = frame_id +
"_" + std::to_string(i + 1);
44 cloud_.reset(
new sensor_msgs::PointCloud2());
52 cloud_.reset(
new sensor_msgs::PointCloud2());
57 int inclination_angle)
59 geometry_msgs::TransformStamped transform;
62 transform.header.frame_id = parent.c_str();
63 transform.child_frame_id = child.c_str();
64 transform.transform.translation.x = 0;
65 transform.transform.translation.y = 0;
66 transform.transform.translation.z = 0;
69 double ang = inclination_angle / 10000.0 * M_PI / 180.0;
71 transform.transform.rotation.x = quat.x();
72 transform.transform.rotation.y = quat.y();
73 transform.transform.rotation.z = quat.z();
74 transform.transform.rotation.w = quat.w();
86 bool apply_correction)
90 sensor_msgs::PointCloud2 c;
107 if (!
cloud_->data.empty())
111 cloud_.reset(
new sensor_msgs::PointCloud2());
124 c1.header.frame_id = c2.header.frame_id;
125 c1.height = c2.height;
127 c1.is_bigendian = c2.is_bigendian;
128 c1.point_step = c2.point_step;
129 c1.row_step = c2.row_step;
131 c1.fields = std::move(c2.fields);
132 c1.data = std::move(c2.data);
137 pcl::PCLPointCloud2 p1, p2;
139 pcl::PointCloud<pcl::PointXYZI>::Ptr p1_cloud(
new pcl::PointCloud<pcl::PointXYZI>);
142 pcl::fromPCLPointCloud2(p1, *p1_cloud);
145 pcl::PointCloud<pcl::PointXYZI>::Ptr p2_cloud(
new pcl::PointCloud<pcl::PointXYZI>);
146 pcl::fromPCLPointCloud2(p2, *p2_cloud);
148 *p1_cloud += *p2_cloud;
153 const int layer_inclination)
155 pcl::PCLPointCloud2 p;
157 pcl::PointCloud<pcl::PointXYZI>::Ptr p_cloud(
new pcl::PointCloud<pcl::PointXYZI>);
160 pcl::fromPCLPointCloud2(p, *p_cloud);
164 double angle_v_deg = layer_inclination / 10000.0;
165 double angle_v = (M_PI / 180.0) * angle_v_deg;
167 for (
size_t i = 0; i < msg->ranges.size(); i++)
171 if (msg->ranges[i] < msg->range_min || msg->ranges[i] >= msg->range_max)
175 double angle_h = msg->angle_min + msg->angle_increment * (double)i;
180 p_cloud->points[cl_idx].x = cos(angle_h) * cos(angle_v) * msg->ranges[i];
181 p_cloud->points[cl_idx].y = sin(angle_h) * cos(angle_v) * msg->ranges[i];
182 p_cloud->points[cl_idx].z = sin(angle_v) * msg->ranges[i];