sick_ldmrs_all_layer_assembler.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016, DFKI GmbH
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  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of DFKI GmbH nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Authors:
30  * Martin Günther <martin.guenther@dfki.de>
31  * Jochen Sprickerhof <ros@jochen.sprickerhof.de>
32  *
33  */
34 
35 #include <ros/ros.h>
36 
37 #include <tf/transform_listener.h>
38 #include <tf/message_filter.h>
40 
42 
43 #include <sensor_msgs/PointCloud2.h>
45 #include <pcl/point_cloud.h>
46 
47 #include <pcl_ros/transforms.h>
48 #include <pcl_ros/impl/transforms.hpp> // necessary because of custom point type
49 
51 typedef pcl::PointCloud<PointT> PointCloudT;
52 
55 
56 std::string fixed_frame_;
57 
58 PointCloudT::Ptr cloud_lower_ = boost::make_shared<PointCloudT>();
59 
60 void callback(const sensor_msgs::PointCloud2::ConstPtr& pc)
61 {
62  PointCloudT::Ptr cloud = boost::make_shared<PointCloudT>();
63  pcl::fromROSMsg(*pc, *cloud);
64 
65  // ----- transform to fixed frame
66  try
67  {
68  PointCloudT::Ptr cloud_fixed = boost::make_shared<PointCloudT>();
69 
70  if (!pcl_ros::transformPointCloud(fixed_frame_, *cloud, *cloud_fixed, *tf_))
71  {
72  ROS_WARN("TF exception in transformPointCloud!");
73  cloud_lower_.reset();
74  return ;
75  }
76  cloud = cloud_fixed;
77  }
78  catch (tf::TransformException& ex)
79  {
80  ROS_WARN("TF Exception %s", ex.what());
81  cloud_lower_.reset();
82  return ;
83  }
84 
85  // ----- check that we have both clouds (for lower + upper layers)
86  if (cloud->size() == 0)
87  return;
88 
89  if (cloud->at(0).layer < 4)
90  {
91  cloud_lower_ = cloud;
92  return; // wait for upper 4 layer cloud
93  }
94  else if (!cloud_lower_)
95  {
96  return; // wait for lower 4 layer cloud first
97  }
98 
99  // ----- concatenate lower + upper clouds
100  *cloud_lower_ += *cloud;
101 
102  // ----- publish
103  sensor_msgs::PointCloud2::Ptr msg = boost::make_shared<sensor_msgs::PointCloud2>();
104  pcl::toROSMsg(*cloud_lower_, *msg);
105  msg->header.stamp = pc->header.stamp;
106  msg->header.frame_id = fixed_frame_;
107  pub_.publish(msg);
108 
109  cloud_lower_.reset();
110 }
111 
112 int main(int argc, char **argv)
113 {
114  ros::init(argc, argv, "sick_ldmrs_all_layer_assembler");
115  ros::NodeHandle nh;
116  ros::NodeHandle private_nh("~");
117 
118  if (!private_nh.getParam("fixed_frame", fixed_frame_))
119  {
120  ROS_FATAL("Need to set parameter fixed_frame");
121  return 1;
122  }
123 
124  tf_ = new tf::TransformListener(nh, ros::Duration(3.0));
125 
128 
129  sub.subscribe(nh, "cloud", 10);
131  tf_filter->registerCallback(boost::bind(callback, _1));
132 
133  pub_ = nh.advertise<sensor_msgs::PointCloud2>("all_layers", 10);
134 
135  ros::spin();
136 
137  delete tf_filter;
138  delete tf_;
139 
140  return 0;
141 }
msg
#define ROS_FATAL(...)
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
sick_ldmrs_msgs::SICK_LDMRS_Point PointT
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
#define ROS_WARN(...)
ros::Publisher pub_
ROSCPP_DECL void spin(Spinner &spinner)
std::string fixed_frame_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
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 callback(const sensor_msgs::PointCloud2::ConstPtr &pc)
tf::TransformListener * tf_
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
bool getParam(const std::string &key, std::string &s) const
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
PointCloudT::Ptr cloud_lower_
pcl::PointCloud< PointT > PointCloudT
Connection registerCallback(const C &callback)


sick_ldmrs_tools
Author(s): Martin Günther , Jochen Sprickerhof
autogenerated on Sun Oct 25 2020 03:33:58