convert.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 // 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 
00039 #ifndef VELODYNE_POINTCLOUD_CONVERT_H
00040 #define VELODYNE_POINTCLOUD_CONVERT_H
00041 
00042 #include <string>
00043 
00044 #include <ros/ros.h>
00045 #include <diagnostic_updater/diagnostic_updater.h>
00046 #include <diagnostic_updater/publisher.h>
00047 
00048 #include <sensor_msgs/PointCloud2.h>
00049 #include <velodyne_pointcloud/rawdata.h>
00050 
00051 #include <dynamic_reconfigure/server.h>
00052 #include <velodyne_pointcloud/CloudNodeConfig.h>
00053 
00054 namespace velodyne_pointcloud
00055 {
00056 class Convert
00057 {
00058   public:
00059     Convert(ros::NodeHandle node, ros::NodeHandle private_nh);
00060     ~Convert() {}
00061 
00062   private:
00063     void callback(velodyne_pointcloud::CloudNodeConfig &config, uint32_t level);
00064     void processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg);
00065 
00066     boost::shared_ptr<dynamic_reconfigure::Server<velodyne_pointcloud::CloudNodeConfig> > srv_;
00067 
00068     boost::shared_ptr<velodyne_rawdata::RawData> data_;
00069     ros::Subscriber velodyne_scan_;
00070     ros::Publisher output_;
00071 
00072     boost::shared_ptr<velodyne_rawdata::DataContainerBase> container_ptr_;
00073 
00074     boost::mutex reconfigure_mtx_;
00075 
00077     typedef struct
00078     {
00079       std::string target_frame;      
00080       std::string fixed_frame;       
00081       bool organize_cloud;           
00082       double max_range;              
00083       double min_range;              
00084       uint16_t num_lasers;           
00085       int npackets;                  
00086     }
00087     Config;
00088     Config config_;
00089     bool first_rcfg_call;
00090 
00091   // diagnostics updater
00092   diagnostic_updater::Updater diagnostics_;
00093   double diag_min_freq_;
00094   double diag_max_freq_;
00095   boost::shared_ptr<diagnostic_updater::TopicDiagnostic> diag_topic_;
00096 };
00097 }  // namespace velodyne_pointcloud
00098 
00099 #endif  // VELODYNE_POINTCLOUD_CONVERT_H


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