transform.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 // Sebastian Pütz 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 
40 #ifndef VELODYNE_POINTCLOUD_TRANSFORM_H
41 #define VELODYNE_POINTCLOUD_TRANSFORM_H
42 
43 #include <string>
44 #include <ros/ros.h>
45 #include "tf/message_filter.h"
49 #include <sensor_msgs/PointCloud2.h>
50 
53 
54 #include <dynamic_reconfigure/server.h>
55 #include <velodyne_pointcloud/TransformNodeConfig.h>
56 
57 namespace velodyne_pointcloud
58 {
59 using TransformNodeCfg = velodyne_pointcloud::TransformNodeConfig;
60 
61 class Transform
62 {
63 public:
64  Transform(
65  ros::NodeHandle node,
66  ros::NodeHandle private_nh,
67  std::string const & node_name = ros::this_node::getName());
69  {
70  }
71 
72 private:
73  void processScan(const velodyne_msgs::VelodyneScan::ConstPtr& scanMsg);
74 
75  // Pointer to dynamic reconfigure service srv_
77  void reconfigure_callback(velodyne_pointcloud::TransformNodeConfig& config, uint32_t level);
78 
79  const std::string tf_prefix_;
85 
87  typedef struct
88  {
89  std::string target_frame;
90  std::string fixed_frame;
92  double max_range;
93  double min_range;
94  uint16_t num_lasers;
95  }
96  Config;
98 
100 
102 
103  // diagnostics updater
108  boost::mutex reconfigure_mtx_;
109 };
110 } // namespace velodyne_pointcloud
111 
112 #endif // VELODYNE_POINTCLOUD_TRANSFORM_H
configuration parameters
Definition: transform.h:87
double min_range
minimum range to publish
Definition: transform.h:93
boost::shared_ptr< tf::TransformListener > tf_ptr_
Definition: transform.h:84
Interfaces for interpreting raw packets from the Velodyne 3D LIDAR.
velodyne_pointcloud::TransformNodeConfig TransformNodeCfg
Definition: transform.h:59
Transform(ros::NodeHandle node, ros::NodeHandle private_nh, std::string const &node_name=ros::this_node::getName())
Constructor.
Definition: transform.cc:29
boost::shared_ptr< dynamic_reconfigure::Server< velodyne_pointcloud::TransformNodeConfig > > srv_
Definition: transform.h:76
boost::shared_ptr< tf::MessageFilter< velodyne_msgs::VelodyneScan > > tf_filter_ptr_
Definition: transform.h:83
message_filters::Subscriber< velodyne_msgs::VelodyneScan > velodyne_scan_
Definition: transform.h:81
std::string fixed_frame
fixed frame
Definition: transform.h:90
ROSCPP_DECL const std::string & getName()
diagnostic_updater::Updater diagnostics_
Definition: transform.h:104
bool organize_cloud
enable/disable organized cloud structure
Definition: transform.h:91
boost::shared_ptr< velodyne_rawdata::RawData > data_
Definition: transform.h:80
std::string target_frame
target frame
Definition: transform.h:89
void reconfigure_callback(velodyne_pointcloud::TransformNodeConfig &config, uint32_t level)
Definition: transform.cc:94
const std::string tf_prefix_
Definition: transform.h:79
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > diag_topic_
Definition: transform.h:107
double max_range
maximum range to publish
Definition: transform.h:92
void processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
Callback for raw scan messages.
Definition: transform.cc:135
uint16_t num_lasers
number of lasers
Definition: transform.h:94
boost::shared_ptr< velodyne_rawdata::DataContainerBase > container_ptr
Definition: transform.h:101


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Sun Sep 6 2020 03:25:30