scan_unifier_node.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016  
00017 
00018 #ifndef SCAN_UNIFIER_NODE_H
00019 #define SCAN_UNIFIER_NODE_H
00020 
00021 //##################
00022 //#### includes ####
00023 
00024 // standard includes
00025 #include <pthread.h>
00026 #include <XmlRpc.h>
00027 #include <math.h>
00028 
00029 // ROS includes
00030 #include <ros/ros.h>
00031 #include <tf/transform_listener.h>
00032 #include <tf/tf.h>
00033 #include <tf/transform_datatypes.h>
00034 #include <sensor_msgs/PointCloud.h>
00035 #include <laser_geometry/laser_geometry.h>
00036 #include <message_filters/subscriber.h>
00037 #include <message_filters/synchronizer.h>
00038 #include <message_filters/sync_policies/approximate_time.h>
00039 
00040 // ROS message includes
00041 #include <sensor_msgs/LaserScan.h>
00042 
00043 
00044 //####################
00045 //#### node class ####
00046 class ScanUnifierNode
00047 {
00048   private:
00058     struct config_struct{
00059       int number_input_scans;
00060       std::vector<std::string> input_scan_topics;
00061     };
00062 
00063     config_struct config_;
00064 
00065     std::string frame_;
00066 
00067     std::vector<message_filters::Subscriber<sensor_msgs::LaserScan>* > message_filter_subscribers_;
00068 
00069     message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::LaserScan,
00070                                                                                   sensor_msgs::LaserScan> >* synchronizer2_;
00071     message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::LaserScan,
00072                                                                                   sensor_msgs::LaserScan,
00073                                                                                   sensor_msgs::LaserScan> >* synchronizer3_;
00074     message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::LaserScan,
00075                                                                                   sensor_msgs::LaserScan,
00076                                                                                   sensor_msgs::LaserScan,
00077                                                                                   sensor_msgs::LaserScan> >* synchronizer4_;
00078 
00079     void messageFilterCallback(const sensor_msgs::LaserScan::ConstPtr& first_scanner,
00080                                const sensor_msgs::LaserScan::ConstPtr& second_scanner);
00081     void messageFilterCallback(const sensor_msgs::LaserScan::ConstPtr& first_scanner,
00082                                const sensor_msgs::LaserScan::ConstPtr& second_scanner,
00083                                const sensor_msgs::LaserScan::ConstPtr& third_scanner);
00084     void messageFilterCallback(const sensor_msgs::LaserScan::ConstPtr& first_scanner,
00085                                const sensor_msgs::LaserScan::ConstPtr& second_scanner,
00086                                const sensor_msgs::LaserScan::ConstPtr& third_scanner,
00087                                const sensor_msgs::LaserScan::ConstPtr& fourth_scanner);
00088 
00089   public:
00090 
00091     // constructor
00092     ScanUnifierNode();
00093 
00094     // destructor
00095     ~ScanUnifierNode();
00096 
00097     /* ----------------------------------- */
00098     /* --------- ROS Variables ----------- */
00099     /* ----------------------------------- */
00100 
00101     // create node handles
00102     ros::NodeHandle nh_, pnh_;
00103 
00104     // declaration of ros publishers
00105     ros::Publisher topicPub_LaserUnified_;
00106 
00107     // tf listener
00108     tf::TransformListener listener_;
00109 
00110     // laser geometry projector
00111     laser_geometry::LaserProjection projector_;
00112 
00113     /* ----------------------------------- */
00114     /* ----------- functions ------------- */
00115     /* ----------------------------------- */
00116 
00124     void getParams();
00125 
00134     bool unifyLaserScans(std::vector<sensor_msgs::LaserScan::ConstPtr> current_scans, sensor_msgs::LaserScan &unified_scan);
00135 
00136 };
00137 #endif


cob_scan_unifier
Author(s): Florian Mirus
autogenerated on Sat Jun 8 2019 21:02:20