convert.h
Go to the documentation of this file.
1 // Copyright (C) 2009, 2010, 2011, 2012, 2019 Austin Robot Technology, Jack O'Quin, Jesse Vera, Joshua Whitley
2 // All rights reserved.
3 //
4 // Software License Agreement (BSD License 2.0)
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions
8 // are met:
9 //
10 // * Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 // * Redistributions in binary form must reproduce the above
13 // copyright notice, this list of conditions and the following
14 // disclaimer in the documentation and/or other materials provided
15 // with the distribution.
16 // * Neither the name of {copyright_holder} nor the names of its
17 // contributors may be used to endorse or promote products derived
18 // from this software without specific prior written permission.
19 //
20 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 // POSSIBILITY OF SUCH DAMAGE.
32 
39 #ifndef VELODYNE_POINTCLOUD_CONVERT_H
40 #define VELODYNE_POINTCLOUD_CONVERT_H
41 
42 #include <string>
43 
44 #include <ros/ros.h>
47 
48 #include <sensor_msgs/PointCloud2.h>
50 
51 #include <dynamic_reconfigure/server.h>
52 #include <velodyne_pointcloud/CloudNodeConfig.h>
53 
54 namespace velodyne_pointcloud
55 {
56 class Convert
57 {
58  public:
59  Convert(ros::NodeHandle node, ros::NodeHandle private_nh);
60  ~Convert() {}
61 
62  private:
63  void callback(velodyne_pointcloud::CloudNodeConfig &config, uint32_t level);
64  void processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg);
65 
67 
71 
73 
74  boost::mutex reconfigure_mtx_;
75 
77  typedef struct
78  {
79  std::string target_frame;
80  std::string fixed_frame;
82  double max_range;
83  double min_range;
84  uint16_t num_lasers;
85  int npackets;
86  }
87  Config;
90 
91  // diagnostics updater
96 };
97 } // namespace velodyne_pointcloud
98 
99 #endif // VELODYNE_POINTCLOUD_CONVERT_H
Interfaces for interpreting raw packets from the Velodyne 3D LIDAR.
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > diag_topic_
Definition: convert.h:95
boost::shared_ptr< velodyne_rawdata::DataContainerBase > container_ptr_
Definition: convert.h:72
boost::mutex reconfigure_mtx_
Definition: convert.h:74
ros::Publisher output_
Definition: convert.h:70
double max_range
maximum range to publish
Definition: convert.h:82
std::string target_frame
target frame
Definition: convert.h:79
void callback(velodyne_pointcloud::CloudNodeConfig &config, uint32_t level)
Definition: convert.cc:86
void processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
Callback for raw scan messages.
Definition: convert.cc:122
bool organize_cloud
enable/disable organized cloud structure
Definition: convert.h:81
uint16_t num_lasers
number of lasers
Definition: convert.h:84
double min_range
minimum range to publish
Definition: convert.h:83
Convert(ros::NodeHandle node, ros::NodeHandle private_nh)
Constructor.
Definition: convert.cc:24
diagnostic_updater::Updater diagnostics_
Definition: convert.h:92
configuration parameters
Definition: convert.h:77
int npackets
number of packets to combine
Definition: convert.h:85
boost::shared_ptr< velodyne_rawdata::RawData > data_
Definition: convert.h:68
std::string fixed_frame
fixed frame
Definition: convert.h:80
ros::Subscriber velodyne_scan_
Definition: convert.h:69
boost::shared_ptr< dynamic_reconfigure::Server< velodyne_pointcloud::CloudNodeConfig > > srv_
Definition: convert.h:66


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Thu Jul 4 2019 19:09:30