sick_ldmrs_all_layer_assembler.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2016, DFKI GmbH
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of DFKI GmbH nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  *      Authors:
00030  *         Martin Günther <martin.guenther@dfki.de>
00031  *         Jochen Sprickerhof <ros@jochen.sprickerhof.de>
00032  *
00033  */
00034 
00035 #include <ros/ros.h>
00036 
00037 #include <tf/transform_listener.h>
00038 #include <tf/message_filter.h>
00039 #include <message_filters/subscriber.h>
00040 
00041 #include <pcl_conversions/pcl_conversions.h>
00042 
00043 #include <sensor_msgs/PointCloud2.h>
00044 #include <sick_ldmrs_msgs/sick_ldmrs_point_type.h>
00045 #include <pcl/point_cloud.h>
00046 
00047 #include <pcl_ros/transforms.h>
00048 #include <pcl_ros/impl/transforms.hpp>   // necessary because of custom point type
00049 
00050 typedef sick_ldmrs_msgs::SICK_LDMRS_Point PointT;
00051 typedef pcl::PointCloud<PointT> PointCloudT;
00052 
00053 tf::TransformListener* tf_;
00054 ros::Publisher pub_;
00055 
00056 std::string fixed_frame_;
00057 
00058 PointCloudT::Ptr cloud_lower_ = boost::make_shared<PointCloudT>();
00059 
00060 void callback(const sensor_msgs::PointCloud2::ConstPtr& pc)
00061 {
00062   PointCloudT::Ptr cloud = boost::make_shared<PointCloudT>();
00063   pcl::fromROSMsg(*pc, *cloud);
00064 
00065   // ----- transform to fixed frame
00066   try
00067   {
00068     PointCloudT::Ptr cloud_fixed = boost::make_shared<PointCloudT>();
00069 
00070     if (!pcl_ros::transformPointCloud(fixed_frame_, *cloud, *cloud_fixed, *tf_))
00071     {
00072       ROS_WARN("TF exception in transformPointCloud!");
00073       cloud_lower_.reset();
00074       return ;
00075     }
00076     cloud = cloud_fixed;
00077   }
00078   catch (tf::TransformException& ex)
00079   {
00080     ROS_WARN("TF Exception %s", ex.what());
00081     cloud_lower_.reset();
00082     return ;
00083   }
00084 
00085   // ----- check that we have both clouds (for lower + upper layers)
00086   if (cloud->size() == 0)
00087     return;
00088 
00089   if (cloud->at(0).layer < 4)
00090   {
00091     cloud_lower_ = cloud;
00092     return;   // wait for upper 4 layer cloud
00093   }
00094   else if (!cloud_lower_)
00095   {
00096     return;   // wait for lower 4 layer cloud first
00097   }
00098 
00099   // ----- concatenate lower + upper clouds
00100   *cloud_lower_ += *cloud;
00101 
00102   // ----- publish
00103   sensor_msgs::PointCloud2::Ptr msg = boost::make_shared<sensor_msgs::PointCloud2>();
00104   pcl::toROSMsg(*cloud_lower_, *msg);
00105   msg->header.stamp = pc->header.stamp;
00106   msg->header.frame_id = fixed_frame_;
00107   pub_.publish(msg);
00108 
00109   cloud_lower_.reset();
00110 }
00111 
00112 int main(int argc, char **argv)
00113 {
00114   ros::init(argc, argv, "sick_ldmrs_all_layer_assembler");
00115   ros::NodeHandle nh;
00116   ros::NodeHandle private_nh("~");
00117 
00118   if (!private_nh.getParam("fixed_frame", fixed_frame_))
00119   {
00120     ROS_FATAL("Need to set parameter fixed_frame");
00121     return 1;
00122   }
00123 
00124   tf_ = new tf::TransformListener(nh, ros::Duration(3.0));
00125 
00126   message_filters::Subscriber<sensor_msgs::PointCloud2> sub;
00127   tf::MessageFilter<sensor_msgs::PointCloud2>* tf_filter;
00128 
00129   sub.subscribe(nh, "cloud", 10);
00130   tf_filter = new tf::MessageFilter<sensor_msgs::PointCloud2>(sub, *tf_, fixed_frame_, 10);
00131   tf_filter->registerCallback(boost::bind(callback, _1));
00132 
00133   pub_ = nh.advertise<sensor_msgs::PointCloud2>("all_layers", 10);
00134 
00135   ros::spin();
00136 
00137   delete tf_filter;
00138   delete tf_;
00139 
00140   return 0;
00141 }


sick_ldmrs_tools
Author(s): Martin Günther , Jochen Sprickerhof
autogenerated on Mon Aug 14 2017 02:35:43