20 #include <sensor_msgs/PointCloud2.h>
45 const pcl::PointCloud<velodyne_pcl::PointXYZIRT>::ConstPtr &in_cloud_msg)
47 in_publisher.
publish(in_cloud_msg);
51 pcl::PointCloud<velodyne_pcl::PointXYZIRT>& out_cloud,
54 Eigen::Matrix4f transform;
57 if (&in_cloud != &out_cloud)
59 out_cloud.header = in_cloud.header;
60 out_cloud.is_dense = in_cloud.is_dense;
61 out_cloud.width = in_cloud.width;
62 out_cloud.height = in_cloud.height;
63 out_cloud.points.reserve (out_cloud.points.size ());
64 out_cloud.points.assign (in_cloud.points.begin (), in_cloud.points.end ());
65 out_cloud.sensor_orientation_ = in_cloud.sensor_orientation_;
66 out_cloud.sensor_origin_ = in_cloud.sensor_origin_;
68 if (in_cloud.is_dense)
70 for (
size_t i = 0; i < out_cloud.points.size (); ++i)
73 Eigen::Matrix<float, 3, 1> pt (in_cloud[i].x, in_cloud[i].y, in_cloud[i].z);
74 out_cloud[i].x =
static_cast<float> (transform (0, 0) * pt.coeffRef (0) +
75 transform (0, 1) * pt.coeffRef (1) +
76 transform (0, 2) * pt.coeffRef (2) +
78 out_cloud[i].y =
static_cast<float> (transform (1, 0) * pt.coeffRef (0) +
79 transform (1, 1) * pt.coeffRef (1) +
80 transform (1, 2) * pt.coeffRef (2) +
82 out_cloud[i].z =
static_cast<float> (transform (2, 0) * pt.coeffRef (0) +
83 transform (2, 1) * pt.coeffRef (1) +
84 transform (2, 2) * pt.coeffRef (2) +
91 for (
size_t i = 0; i < out_cloud.points.size (); ++i)
93 if (!pcl_isfinite (in_cloud.points[i].x) ||
94 !pcl_isfinite (in_cloud.points[i].y) ||
95 !pcl_isfinite (in_cloud.points[i].z))
98 Eigen::Matrix<float, 3, 1> pt (in_cloud[i].x, in_cloud[i].y, in_cloud[i].z);
99 out_cloud[i].x =
static_cast<float> (transform (0, 0) * pt.coeffRef (0) +
100 transform (0, 1) * pt.coeffRef (1) +
101 transform (0, 2) * pt.coeffRef (2) +
103 out_cloud[i].y =
static_cast<float> (transform (1, 0) * pt.coeffRef (0) +
104 transform (1, 1) * pt.coeffRef (1) +
105 transform (1, 2) * pt.coeffRef (2) +
107 out_cloud[i].z =
static_cast<float> (transform (2, 0) * pt.coeffRef (0) +
108 transform (2, 1) * pt.coeffRef (1) +
109 transform (2, 2) * pt.coeffRef (2) +
115 void CloudCallback(
const pcl::PointCloud<velodyne_pcl::PointXYZIRT>::ConstPtr &in_sensor_cloud)
117 pcl::PointCloud<velodyne_pcl::PointXYZIRT>::Ptr transformed_cloud_ptr (
new pcl::PointCloud<velodyne_pcl::PointXYZIRT>);
119 bool do_transform =
false;
129 ROS_ERROR(
"cloud_transformer: %s NOT Transforming.", ex.what());
130 do_transform =
false;
142 { pcl::copyPointCloud(*in_sensor_cloud, *transformed_cloud_ptr);}
154 ROS_INFO(
"Initializing Cloud Transformer, please wait...");
177 int main(
int argc,
char **argv)
179 ros::init(argc, argv,
"cloud_transformer");