cloud_transformer_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017-2019 Autoware Foundation. All rights reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  ********************
16  * v1.0: amc-nu (abrahammonrroy@yahoo.com)
17  */
18 #include <iostream>
19 #include <ros/ros.h>
20 #include <sensor_msgs/PointCloud2.h>
21 #include <pcl_ros/point_cloud.h>
23 #include <pcl/point_types.h>
25 #include <tf/transform_listener.h>
26 #include <pcl_ros/transforms.h>
27 
29 {
30 private:
31 
35 
36  std::string input_point_topic_;
37  std::string target_frame_;
38  std::string output_point_topic_;
39 
41 
43 
44  void publish_cloud(const ros::Publisher& in_publisher,
45  const pcl::PointCloud<velodyne_pcl::PointXYZIRT>::ConstPtr &in_cloud_msg)
46  {
47  in_publisher.publish(in_cloud_msg);
48  }
49 
50  void transformXYZIRCloud(const pcl::PointCloud<velodyne_pcl::PointXYZIRT>& in_cloud,
51  pcl::PointCloud<velodyne_pcl::PointXYZIRT>& out_cloud,
52  const tf::StampedTransform& in_tf_stamped_transform)
53  {
54  Eigen::Matrix4f transform;
55  pcl_ros::transformAsMatrix(in_tf_stamped_transform, transform);
56 
57  if (&in_cloud != &out_cloud)
58  {
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_;
67  }
68  if (in_cloud.is_dense)
69  {
70  for (size_t i = 0; i < out_cloud.points.size (); ++i)
71  {
72  //out_cloud.points[i].getVector3fMap () = transform * in_cloud.points[i].getVector3fMap ();
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) +
77  transform (0, 3));
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) +
81  transform (1, 3));
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) +
85  transform (2, 3));
86  }
87  }
88  else
89  {
90  // Dataset might contain NaNs and Infs, so check for them first,
91  for (size_t i = 0; i < out_cloud.points.size (); ++i)
92  {
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))
96  {continue;}
97  //out_cloud.points[i].getVector3fMap () = transform * in_cloud.points[i].getVector3fMap ();
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) +
102  transform (0, 3));
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) +
106  transform (1, 3));
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) +
110  transform (2, 3));
111  }
112  }
113  }
114 
115  void CloudCallback(const pcl::PointCloud<velodyne_pcl::PointXYZIRT>::ConstPtr &in_sensor_cloud)
116  {
117  pcl::PointCloud<velodyne_pcl::PointXYZIRT>::Ptr transformed_cloud_ptr (new pcl::PointCloud<velodyne_pcl::PointXYZIRT>);
118 
119  bool do_transform = false;
120  tf::StampedTransform transform;
121  if (target_frame_ != in_sensor_cloud->header.frame_id)
122  {
123  try {
124  tf_listener_ptr_->lookupTransform(target_frame_, in_sensor_cloud->header.frame_id, ros::Time(0),
125  transform);
126  do_transform = true;
127  }
128  catch (tf::TransformException ex) {
129  ROS_ERROR("cloud_transformer: %s NOT Transforming.", ex.what());
130  do_transform = false;
131  transform_ok_ = false;
132  }
133  }
134  if (do_transform)
135  {
136  transformXYZIRCloud(*in_sensor_cloud, *transformed_cloud_ptr, transform);
137  transformed_cloud_ptr->header.frame_id = target_frame_;
138  if (!transform_ok_)
139  {ROS_INFO("cloud_transformer: Correctly Transformed"); transform_ok_=true;}
140  }
141  else
142  { pcl::copyPointCloud(*in_sensor_cloud, *transformed_cloud_ptr);}
143 
144  publish_cloud(transformed_points_pub_, transformed_cloud_ptr);
145  }
146 
147 public:
149  {
150  tf_listener_ptr_ = in_tf_listener_ptr;
151  }
152  void Run()
153  {
154  ROS_INFO("Initializing Cloud Transformer, please wait...");
155  node_handle_.param<std::string>("input_point_topic", input_point_topic_, "/points_raw");
156  ROS_INFO("Input point_topic: %s", input_point_topic_.c_str());
157 
158  node_handle_.param<std::string>("target_frame", target_frame_, "velodyne");
159  ROS_INFO("Target Frame in TF (target_frame) : %s", target_frame_.c_str());
160 
161  node_handle_.param<std::string>("output_point_topic", output_point_topic_, "/points_transformed");
162  ROS_INFO("output_point_topic: %s", output_point_topic_.c_str());
163 
164  ROS_INFO("Subscribing to... %s", input_point_topic_.c_str());
166 
167  transformed_points_pub_ = node_handle_.advertise<sensor_msgs::PointCloud2>(output_point_topic_, 2);
168 
169  ROS_INFO("Ready");
170 
171  ros::spin();
172 
173  }
174 
175 };
176 
177 int main(int argc, char **argv)
178 {
179  ros::init(argc, argv, "cloud_transformer");
180  tf::TransformListener tf_listener;
181  CloudTransformerNode app(&tf_listener);
182 
183  app.Run();
184 
185  return 0;
186 
187 }
pcl_ros::transformAsMatrix
void transformAsMatrix(const geometry_msgs::Transform &bt, Eigen::Matrix4f &out_mat)
CloudTransformerNode::transformXYZIRCloud
void transformXYZIRCloud(const pcl::PointCloud< velodyne_pcl::PointXYZIRT > &in_cloud, pcl::PointCloud< velodyne_pcl::PointXYZIRT > &out_cloud, const tf::StampedTransform &in_tf_stamped_transform)
Definition: cloud_transformer_node.cpp:50
CloudTransformerNode::transform_ok_
bool transform_ok_
Definition: cloud_transformer_node.cpp:42
ros::Publisher
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
CloudTransformerNode
Definition: cloud_transformer_node.cpp:28
CloudTransformerNode::input_point_topic_
std::string input_point_topic_
Definition: cloud_transformer_node.cpp:36
tf::StampedTransform
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
transforms.h
point_cloud.h
CloudTransformerNode::target_frame_
std::string target_frame_
Definition: cloud_transformer_node.cpp:37
CloudTransformerNode::CloudCallback
void CloudCallback(const pcl::PointCloud< velodyne_pcl::PointXYZIRT >::ConstPtr &in_sensor_cloud)
Definition: cloud_transformer_node.cpp:115
main
int main(int argc, char **argv)
Definition: cloud_transformer_node.cpp:177
CloudTransformerNode::CloudTransformerNode
CloudTransformerNode(tf::TransformListener *in_tf_listener_ptr)
Definition: cloud_transformer_node.cpp:148
CloudTransformerNode::points_node_sub_
ros::Subscriber points_node_sub_
Definition: cloud_transformer_node.cpp:33
point_types.h
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
CloudTransformerNode::transformed_points_pub_
ros::Publisher transformed_points_pub_
Definition: cloud_transformer_node.cpp:34
app
app
CloudTransformerNode::Run
void Run()
Definition: cloud_transformer_node.cpp:152
CloudTransformerNode::publish_cloud
void publish_cloud(const ros::Publisher &in_publisher, const pcl::PointCloud< velodyne_pcl::PointXYZIRT >::ConstPtr &in_cloud_msg)
Definition: cloud_transformer_node.cpp:44
transform_listener.h
CloudTransformerNode::tf_listener_ptr_
tf::TransformListener * tf_listener_ptr_
Definition: cloud_transformer_node.cpp:40
ros::Time
CloudTransformerNode::node_handle_
ros::NodeHandle node_handle_
Definition: cloud_transformer_node.cpp:32
ROS_ERROR
#define ROS_ERROR(...)
tf::TransformListener
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::spin
ROSCPP_DECL void spin()
CloudTransformerNode::output_point_topic_
std::string output_point_topic_
Definition: cloud_transformer_node.cpp:38
tf::Transformer::lookupTransform
void lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, StampedTransform &transform) const
tf2::TransformException
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle
ros::Subscriber
pcl_conversions.h


points_preprocessor
Author(s): n-patiphon , aohsato
autogenerated on Wed Mar 2 2022 00:12:07