transform.h
Go to the documentation of this file.
00001 // Copyright (C) 2009, 2010, 2011, 2012, 2019 Austin Robot Technology, Jack O'Quin, Jesse Vera, Joshua Whitley,
00002 // Sebastian Pütz All rights reserved.
00003 //
00004 // Software License Agreement (BSD License 2.0)
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions
00008 // are met:
00009 //
00010 //  * Redistributions of source code must retain the above copyright
00011 //    notice, this list of conditions and the following disclaimer.
00012 //  * Redistributions in binary form must reproduce the above
00013 //    copyright notice, this list of conditions and the following
00014 //    disclaimer in the documentation and/or other materials provided
00015 //    with the distribution.
00016 //  * Neither the name of {copyright_holder} nor the names of its
00017 //    contributors may be used to endorse or promote products derived
00018 //    from this software without specific prior written permission.
00019 //
00020 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 // POSSIBILITY OF SUCH DAMAGE.
00032 
00040 #ifndef VELODYNE_POINTCLOUD_TRANSFORM_H
00041 #define VELODYNE_POINTCLOUD_TRANSFORM_H
00042 
00043 #include <string>
00044 #include <ros/ros.h>
00045 #include "tf/message_filter.h"
00046 #include "message_filters/subscriber.h"
00047 #include <diagnostic_updater/diagnostic_updater.h>
00048 #include <diagnostic_updater/publisher.h>
00049 #include <sensor_msgs/PointCloud2.h>
00050 
00051 #include <velodyne_pointcloud/rawdata.h>
00052 #include <velodyne_pointcloud/pointcloudXYZIR.h>
00053 
00054 #include <dynamic_reconfigure/server.h>
00055 #include <velodyne_pointcloud/TransformNodeConfig.h>
00056 
00057 namespace velodyne_pointcloud
00058 {
00059 using TransformNodeCfg = velodyne_pointcloud::TransformNodeConfig;
00060 
00061 class Transform
00062 {
00063 public:
00064   Transform(ros::NodeHandle node, ros::NodeHandle private_nh);
00065   ~Transform()
00066   {
00067   }
00068 
00069 private:
00070   void processScan(const velodyne_msgs::VelodyneScan::ConstPtr& scanMsg);
00071 
00072   // Pointer to dynamic reconfigure service srv_
00073   boost::shared_ptr<dynamic_reconfigure::Server<velodyne_pointcloud::TransformNodeConfig>> srv_;
00074   void reconfigure_callback(velodyne_pointcloud::TransformNodeConfig& config, uint32_t level);
00075 
00076   const std::string tf_prefix_;
00077   boost::shared_ptr<velodyne_rawdata::RawData> data_;
00078   message_filters::Subscriber<velodyne_msgs::VelodyneScan> velodyne_scan_;
00079   ros::Publisher output_;
00080   boost::shared_ptr<tf::MessageFilter<velodyne_msgs::VelodyneScan>> tf_filter_ptr_;
00081   boost::shared_ptr<tf::TransformListener> tf_ptr_;
00082 
00084   typedef struct
00085   {
00086     std::string target_frame;  
00087     std::string fixed_frame;   
00088     bool organize_cloud;       
00089     double max_range;          
00090     double min_range;          
00091     uint16_t num_lasers;       
00092   }
00093   Config;
00094   Config config_;
00095 
00096   bool first_rcfg_call;
00097 
00098   boost::shared_ptr<velodyne_rawdata::DataContainerBase> container_ptr;
00099 
00100   // diagnostics updater
00101   diagnostic_updater::Updater diagnostics_;
00102   double diag_min_freq_;
00103   double diag_max_freq_;
00104   boost::shared_ptr<diagnostic_updater::TopicDiagnostic> diag_topic_;
00105   boost::mutex reconfigure_mtx_;
00106 };
00107 }  // namespace velodyne_pointcloud
00108 
00109 #endif  // VELODYNE_POINTCLOUD_TRANSFORM_H


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Wed Jul 3 2019 19:32:23