point_cloud_aggregator.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2019, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <ros/ros.h>
30 #include <nodelet/nodelet.h>
31 
32 #include <pcl/point_cloud.h>
33 #include <pcl/point_types.h>
35 #include <pcl/io/pcd_io.h>
36 
37 #include <pcl_ros/transforms.h>
38 
39 #include <tf/transform_listener.h>
40 
41 #include <sensor_msgs/PointCloud2.h>
42 
45 
49 
52 
53 namespace rtabmap_ros
54 {
55 
63 {
64 public:
66  warningThread_(0),
68  exactSync4_(0),
69  approxSync4_(0),
70  exactSync3_(0),
71  approxSync3_(0),
72  exactSync2_(0),
73  approxSync2_(0)
74  {}
75 
77  {
78  delete exactSync4_;
79  delete approxSync4_;
80  delete exactSync3_;
81  delete approxSync3_;
82  delete exactSync2_;
83  delete approxSync2_;
84 
85  if(warningThread_)
86  {
87  callbackCalled_=true;
88  warningThread_->join();
89  delete warningThread_;
90  }
91  }
92 
93 private:
94  virtual void onInit()
95  {
98 
99  int queueSize = 5;
100  int count = 2;
101  bool approx=true;
102  pnh.param("queue_size", queueSize, queueSize);
103  pnh.param("frame_id", frameId_, frameId_);
104  pnh.param("fixed_frame_id", fixedFrameId_, fixedFrameId_);
105  pnh.param("approx_sync", approx, approx);
106  pnh.param("count", count, count);
107 
108  cloudSub_1_.subscribe(nh, "cloud1", 1);
109  cloudSub_2_.subscribe(nh, "cloud2", 1);
110 
111  std::string subscribedTopicsMsg;
112  if(count == 4)
113  {
114  cloudSub_3_.subscribe(nh, "cloud3", 1);
115  cloudSub_4_.subscribe(nh, "cloud4", 1);
116  if(approx)
117  {
119  approxSync4_->registerCallback(boost::bind(&rtabmap_ros::PointCloudAggregator::clouds4_callback, this, _1, _2, _3, _4));
120  }
121  else
122  {
124  exactSync4_->registerCallback(boost::bind(&rtabmap_ros::PointCloudAggregator::clouds4_callback, this, _1, _2, _3, _4));
125  }
126  subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync):\n %s,\n %s,\n %s,\n %s",
127  getName().c_str(),
128  approx?"approx":"exact",
129  cloudSub_1_.getTopic().c_str(),
130  cloudSub_2_.getTopic().c_str(),
131  cloudSub_3_.getTopic().c_str(),
132  cloudSub_4_.getTopic().c_str());
133  }
134  else if(count == 3)
135  {
136  cloudSub_3_.subscribe(nh, "cloud3", 1);
137  if(approx)
138  {
140  approxSync3_->registerCallback(boost::bind(&rtabmap_ros::PointCloudAggregator::clouds3_callback, this, _1, _2, _3));
141  }
142  else
143  {
145  exactSync3_->registerCallback(boost::bind(&rtabmap_ros::PointCloudAggregator::clouds3_callback, this, _1, _2, _3));
146  }
147  subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync):\n %s,\n %s,\n %s",
148  getName().c_str(),
149  approx?"approx":"exact",
150  cloudSub_1_.getTopic().c_str(),
151  cloudSub_2_.getTopic().c_str(),
152  cloudSub_3_.getTopic().c_str());
153  }
154  else
155  {
156  if(approx)
157  {
159  approxSync2_->registerCallback(boost::bind(&rtabmap_ros::PointCloudAggregator::clouds2_callback, this, _1, _2));
160  }
161  else
162  {
164  exactSync2_->registerCallback(boost::bind(&rtabmap_ros::PointCloudAggregator::clouds2_callback, this, _1, _2));
165  }
166  subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync):\n %s,\n %s",
167  getName().c_str(),
168  approx?"approx":"exact",
169  cloudSub_1_.getTopic().c_str(),
170  cloudSub_2_.getTopic().c_str());
171  }
172 
173  cloudPub_ = nh.advertise<sensor_msgs::PointCloud2>("combined_cloud", 1);
174 
175  warningThread_ = new boost::thread(boost::bind(&PointCloudAggregator::warningLoop, this, subscribedTopicsMsg, approx));
176  NODELET_INFO("%s", subscribedTopicsMsg.c_str());
177  }
178 
179  void clouds4_callback(const sensor_msgs::PointCloud2ConstPtr & cloudMsg_1,
180  const sensor_msgs::PointCloud2ConstPtr & cloudMsg_2,
181  const sensor_msgs::PointCloud2ConstPtr & cloudMsg_3,
182  const sensor_msgs::PointCloud2ConstPtr & cloudMsg_4)
183  {
184  std::vector<sensor_msgs::PointCloud2ConstPtr> clouds;
185  clouds.push_back(cloudMsg_1);
186  clouds.push_back(cloudMsg_2);
187  clouds.push_back(cloudMsg_3);
188  clouds.push_back(cloudMsg_4);
189 
190  combineClouds(clouds);
191  }
192  void clouds3_callback(const sensor_msgs::PointCloud2ConstPtr & cloudMsg_1,
193  const sensor_msgs::PointCloud2ConstPtr & cloudMsg_2,
194  const sensor_msgs::PointCloud2ConstPtr & cloudMsg_3)
195  {
196  std::vector<sensor_msgs::PointCloud2ConstPtr> clouds;
197  clouds.push_back(cloudMsg_1);
198  clouds.push_back(cloudMsg_2);
199  clouds.push_back(cloudMsg_3);
200 
201  combineClouds(clouds);
202  }
203  void clouds2_callback(const sensor_msgs::PointCloud2ConstPtr & cloudMsg_1,
204  const sensor_msgs::PointCloud2ConstPtr & cloudMsg_2)
205  {
206  std::vector<sensor_msgs::PointCloud2ConstPtr> clouds;
207  clouds.push_back(cloudMsg_1);
208  clouds.push_back(cloudMsg_2);
209 
210  combineClouds(clouds);
211  }
212  void combineClouds(const std::vector<sensor_msgs::PointCloud2ConstPtr> & cloudMsgs)
213  {
214  callbackCalled_ = true;
215  ROS_ASSERT(cloudMsgs.size() > 1);
217  {
218  pcl::PCLPointCloud2 output;
219 
220  std::string frameId = frameId_;
221  if(!frameId.empty() && frameId.compare(cloudMsgs[0]->header.frame_id) != 0)
222  {
223  sensor_msgs::PointCloud2 tmp;
224  pcl_ros::transformPointCloud(frameId, *cloudMsgs[0], tmp, tfListener_);
225  pcl_conversions::toPCL(tmp, output);
226  }
227  else
228  {
229  pcl_conversions::toPCL(*cloudMsgs[0], output);
230  frameId = cloudMsgs[0]->header.frame_id;
231  }
232 
233  for(unsigned int i=1; i<cloudMsgs.size(); ++i)
234  {
235  rtabmap::Transform cloudDisplacement;
236  bool notsync = false;
237  if(!fixedFrameId_.empty() &&
238  cloudMsgs[0]->header.stamp != cloudMsgs[i]->header.stamp)
239  {
240  // approx sync
241  cloudDisplacement = rtabmap_ros::getTransform(
242  frameId, //sourceTargetFrame
243  fixedFrameId_, //fixedFrame
244  cloudMsgs[i]->header.stamp, //stampSource
245  cloudMsgs[0]->header.stamp, //stampTarget
246  tfListener_,
247  0.1);
248  notsync = true;
249  }
250 
251  pcl::PCLPointCloud2 cloud2;
252  if(frameId.compare(cloudMsgs[i]->header.frame_id) != 0)
253  {
254  sensor_msgs::PointCloud2 tmp;
255  pcl_ros::transformPointCloud(frameId, *cloudMsgs[i], tmp, tfListener_);
256  if(!cloudDisplacement.isNull())
257  {
258  sensor_msgs::PointCloud2 tmp2;
259  pcl_ros::transformPointCloud(cloudDisplacement.toEigen4f(), tmp, tmp2);
260  pcl_conversions::toPCL(tmp2, cloud2);
261  }
262  else
263  {
264  pcl_conversions::toPCL(tmp, cloud2);
265  }
266 
267  }
268  else
269  {
270  if(!cloudDisplacement.isNull())
271  {
272  sensor_msgs::PointCloud2 tmp;
273  pcl_ros::transformPointCloud(cloudDisplacement.toEigen4f(), *cloudMsgs[i], tmp);
274  pcl_conversions::toPCL(tmp, cloud2);
275  }
276  else
277  {
278  pcl_conversions::toPCL(*cloudMsgs[i], cloud2);
279  }
280  }
281 
282  pcl::PCLPointCloud2 tmp_output;
283  pcl::concatenatePointCloud(output, cloud2, tmp_output);
284  output = tmp_output;
285  }
286 
287  sensor_msgs::PointCloud2 rosCloud;
288  pcl_conversions::moveFromPCL(output, rosCloud);
289  rosCloud.header.stamp = cloudMsgs[0]->header.stamp;
290  rosCloud.header.frame_id = frameId;
291  cloudPub_.publish(rosCloud);
292  }
293  }
294 
295  void warningLoop(const std::string & subscribedTopicsMsg, bool approxSync)
296  {
297  ros::Duration r(5.0);
298  while(!callbackCalled_)
299  {
300  r.sleep();
301  if(!callbackCalled_)
302  {
303  ROS_WARN("%s: Did not receive data since 5 seconds! Make sure the input topics are "
304  "published (\"$ rostopic hz my_topic\") and the timestamps in their "
305  "header are set. %s%s",
306  getName().c_str(),
307  approxSync?"":"Parameter \"approx_sync\" is false, which means that input "
308  "topics should have all the exact timestamp for the callback to be called.",
309  subscribedTopicsMsg.c_str());
310  }
311  }
312  }
313 
314  boost::thread * warningThread_;
316 
333 
335 
336  std::string frameId_;
337  std::string fixedFrameId_;
339 };
340 
342 }
343 
message_filters::Synchronizer< ExactSync4Policy > * exactSync4_
std::string getTopic() const
message_filters::Subscriber< sensor_msgs::PointCloud2 > cloudSub_2_
std::string uFormat(const char *fmt,...)
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber< sensor_msgs::PointCloud2 > cloudSub_3_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > ExactSync3Policy
bool sleep() const
const std::string & getName() const
message_filters::Synchronizer< ExactSync2Policy > * exactSync2_
void clouds3_callback(const sensor_msgs::PointCloud2ConstPtr &cloudMsg_1, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_2, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_3)
#define ROS_WARN(...)
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
message_filters::Synchronizer< ApproxSync3Policy > * approxSync3_
ros::NodeHandle & getPrivateNodeHandle() const
void combineClouds(const std::vector< sensor_msgs::PointCloud2ConstPtr > &cloudMsgs)
void clouds4_callback(const sensor_msgs::PointCloud2ConstPtr &cloudMsg_1, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_2, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_3, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_4)
bool isNull() const
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > ApproxSync2Policy
message_filters::Synchronizer< ExactSync3Policy > * exactSync3_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > ExactSync2Policy
bool concatenatePointCloud(const sensor_msgs::PointCloud2 &cloud1, const sensor_msgs::PointCloud2 &cloud2, sensor_msgs::PointCloud2 &cloud_out)
string frameId
Definition: patrol.py:11
#define false
#define NODELET_INFO(...)
uint32_t getNumSubscribers() const
Eigen::Matrix4f toEigen4f() const
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > ApproxSync3Policy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > ExactSync4Policy
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
#define ROS_ASSERT(cond)
void clouds2_callback(const sensor_msgs::PointCloud2ConstPtr &cloudMsg_1, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_2)
message_filters::Synchronizer< ApproxSync2Policy > * approxSync2_
r
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > ApproxSync4Policy
void warningLoop(const std::string &subscribedTopicsMsg, bool approxSync)
message_filters::Subscriber< sensor_msgs::PointCloud2 > cloudSub_4_
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)
message_filters::Subscriber< sensor_msgs::PointCloud2 > cloudSub_1_
message_filters::Synchronizer< ApproxSync4Policy > * approxSync4_


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19