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 
82 
84  typedef struct
85  {
86  std::string target_frame;
87  std::string fixed_frame;
89  double max_range;
90  double min_range;
91  uint16_t num_lasers;
92  }
93  Config;
95 
97 
99 
100  // diagnostics updater
105  boost::mutex reconfigure_mtx_;
106 };
107 } // namespace velodyne_pointcloud
108 
109 #endif // VELODYNE_POINTCLOUD_TRANSFORM_H
velodyne_pointcloud::Transform::diagnostics_
diagnostic_updater::Updater diagnostics_
Definition: transform.h:101
velodyne_pointcloud::Transform::first_rcfg_call
bool first_rcfg_call
Definition: transform.h:96
velodyne_pointcloud
Definition: calibration.h:40
velodyne_pointcloud::Transform::container_ptr
boost::shared_ptr< velodyne_rawdata::DataContainerBase > container_ptr
Definition: transform.h:98
ros::Publisher
boost::shared_ptr
velodyne_pointcloud::Transform::Config::num_lasers
uint16_t num_lasers
number of lasers
Definition: transform.h:91
ros.h
velodyne_pointcloud::Transform::processScan
void processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
Callback for raw scan messages.
Definition: transform.cc:113
velodyne_pointcloud::Transform::diag_max_freq_
double diag_max_freq_
Definition: transform.h:103
diagnostic_updater::Updater
velodyne_pointcloud::Transform::velodyne_scan_
ros::Subscriber velodyne_scan_
Definition: transform.h:80
publisher.h
diagnostic_updater.h
velodyne_pointcloud::Transform::Config::target_frame
std::string target_frame
target frame
Definition: transform.h:86
velodyne_pointcloud::Transform::Transform
Transform(ros::NodeHandle node, ros::NodeHandle private_nh, std::string const &node_name=ros::this_node::getName())
Constructor.
Definition: transform.cc:29
velodyne_pointcloud::Transform::Config::min_range
double min_range
minimum range to publish
Definition: transform.h:90
pointcloudXYZIRT.h
rawdata.h
Interfaces for interpreting raw packets from the Velodyne 3D LIDAR.
message_filter.h
velodyne_pointcloud::Transform
Definition: transform.h:61
subscriber.h
velodyne_pointcloud::TransformNodeCfg
velodyne_pointcloud::TransformNodeConfig TransformNodeCfg
Definition: transform.h:59
velodyne_pointcloud::Transform::reconfigure_callback
void reconfigure_callback(velodyne_pointcloud::TransformNodeConfig &config, uint32_t level)
Definition: transform.cc:70
velodyne_pointcloud::Transform::Config::organize_cloud
bool organize_cloud
enable/disable organized cloud structure
Definition: transform.h:88
velodyne_pointcloud::Transform::output_
ros::Publisher output_
Definition: transform.h:81
velodyne_pointcloud::Transform::Config::fixed_frame
std::string fixed_frame
fixed frame
Definition: transform.h:87
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
velodyne_pointcloud::Transform::config_
Config config_
Definition: transform.h:94
velodyne_pointcloud::Transform::Config
configuration parameters
Definition: transform.h:84
velodyne_pointcloud::Transform::Config::max_range
double max_range
maximum range to publish
Definition: transform.h:89
velodyne_pointcloud::Transform::diag_topic_
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > diag_topic_
Definition: transform.h:104
velodyne_pointcloud::Transform::reconfigure_mtx_
boost::mutex reconfigure_mtx_
Definition: transform.h:105
velodyne_pointcloud::Transform::srv_
boost::shared_ptr< dynamic_reconfigure::Server< velodyne_pointcloud::TransformNodeConfig > > srv_
Definition: transform.h:76
velodyne_pointcloud::Transform::diag_min_freq_
double diag_min_freq_
Definition: transform.h:102
velodyne_pointcloud::Transform::~Transform
~Transform()
Definition: transform.h:68
velodyne_pointcloud::Transform::data_
boost::shared_ptr< velodyne_rawdata::RawData > data_
Definition: transform.h:79
ros::NodeHandle
ros::Subscriber


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Tue May 2 2023 02:28:04