convert.cc
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2009, 2010 Austin Robot Technology, Jack O'Quin
3  * Copyright (C) 2011 Jesse Vera
4  * Copyright (C) 2012 Austin Robot Technology, Jack O'Quin
5  * License: Modified BSD Software License Agreement
6  *
7  * $Id$
8  */
9 
17 
20 
21 namespace velodyne_pointcloud
22 {
24  Convert::Convert(ros::NodeHandle node, ros::NodeHandle private_nh, std::string const & node_name):
25  data_(new velodyne_rawdata::RawData()), first_rcfg_call(true),
26  diagnostics_(node, private_nh, node_name)
27  {
28  // Get startup parameters
29  private_nh.param<std::string>("fixed_frame", config_.fixed_frame, "velodyne");
30  private_nh.param<std::string>("target_Frame", config_.target_frame, "velodyne");
31  private_nh.param<double>("min_range", config_.min_range, 10.0);
32  private_nh.param<double>("max_range", config_.max_range, 200.0);
33  private_nh.param<bool>("organize_cloud", config_.organize_cloud, false);
34 
35  boost::optional<velodyne_pointcloud::Calibration> calibration = data_->setup(private_nh);
36  if(calibration)
37  {
38  ROS_DEBUG_STREAM("Calibration file loaded.");
39  config_.num_lasers = static_cast<uint16_t>(calibration.get().num_lasers);
40  }
41  else
42  {
43  ROS_ERROR_STREAM("Could not load calibration file!");
44  }
45 
47  {
51  config_.num_lasers, data_->scansPerPacket()));
52  }
53  else
54  {
58  data_->scansPerPacket()));
59  }
60 
61 
62  // advertise output point cloud (before subscribing to input data)
63  output_ =
64  node.advertise<sensor_msgs::PointCloud2>("velodyne_points", 10);
65 
66  srv_ = boost::make_shared <dynamic_reconfigure::Server<velodyne_pointcloud::
67  CloudNodeConfig> > (private_nh);
68  dynamic_reconfigure::Server<velodyne_pointcloud::CloudNodeConfig>::
69  CallbackType f;
70  f = boost::bind (&Convert::callback, this, _1, _2);
71  srv_->setCallback (f);
72 
73  // subscribe to VelodyneScan packets
75  node.subscribe("velodyne_packets", 10,
76  &Convert::processScan, (Convert *) this,
77  ros::TransportHints().tcpNoDelay(true));
78 
79  // Diagnostics
80  diagnostics_.setHardwareID("Velodyne Convert");
81  // Arbitrary frequencies since we don't know which RPM is used, and are only
82  // concerned about monitoring the frequency.
83  diag_min_freq_ = 2.0;
84  diag_max_freq_ = 20.0;
85  using namespace diagnostic_updater;
86  diag_topic_.reset(new TopicDiagnostic("velodyne_points", diagnostics_,
89  0.1, 10),
91  }
92 
93  void Convert::callback(velodyne_pointcloud::CloudNodeConfig &config,
94  uint32_t level)
95  {
96  ROS_INFO("Reconfigure Request");
97  data_->setParameters(config.min_range, config.max_range, config.view_direction,
98  config.view_width);
99  config_.fixed_frame = config.fixed_frame;
100  config_.target_frame = config.target_frame;
101  config_.min_range = config.min_range;
102  config_.max_range = config.max_range;
103 
104  if(first_rcfg_call || config.organize_cloud != config_.organize_cloud){
105  first_rcfg_call = false;
106  config_.organize_cloud = config.organize_cloud;
107  if(config_.organize_cloud) // TODO only on change
108  {
109  ROS_INFO_STREAM("Using the organized cloud format...");
113  config_.num_lasers, data_->scansPerPacket()));
114  }
115  else
116  {
120  data_->scansPerPacket()));
121  }
122  }
123 
125 
126  }
127 
129  void Convert::processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
130  {
131  if (output_.getNumSubscribers() == 0) // no one listening?
132  return; // avoid much work
133 
134  boost::lock_guard<boost::mutex> guard(reconfigure_mtx_);
135  // allocate a point cloud with same time and frame ID as raw data
136  container_ptr_->setup(scanMsg);
137 
138  // process each packet provided by the driver
139  for (size_t i = 0; i < scanMsg->packets.size(); ++i)
140  {
141  data_->unpack(scanMsg->packets[i], *container_ptr_, scanMsg->header.stamp);
142  }
143 
144  // publish the accumulated cloud message
145  diag_topic_->tick(scanMsg->header.stamp);
147  output_.publish(container_ptr_->finishCloud());
148  }
149 
150 } // namespace velodyne_pointcloud
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > diag_topic_
Definition: convert.h:98
boost::shared_ptr< velodyne_rawdata::DataContainerBase > container_ptr_
Definition: convert.h:75
boost::mutex reconfigure_mtx_
Definition: convert.h:77
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher output_
Definition: convert.h:73
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
double max_range
maximum range to publish
Definition: convert.h:85
void setHardwareID(const std::string &hwid)
std::string target_frame
target frame
Definition: convert.h:82
void callback(velodyne_pointcloud::CloudNodeConfig &config, uint32_t level)
Definition: convert.cc:93
void processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
Callback for raw scan messages.
Definition: convert.cc:129
bool organize_cloud
enable/disable organized cloud structure
Definition: convert.h:84
uint16_t num_lasers
number of lasers
Definition: convert.h:87
double min_range
minimum range to publish
Definition: convert.h:86
Convert(ros::NodeHandle node, ros::NodeHandle private_nh, std::string const &node_name=ros::this_node::getName())
Constructor.
Definition: convert.cc:24
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
diagnostic_updater::Updater diagnostics_
Definition: convert.h:95
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_DEBUG_STREAM(args)
uint32_t getNumSubscribers() const
#define ROS_INFO_STREAM(args)
boost::shared_ptr< velodyne_rawdata::RawData > data_
Definition: convert.h:71
std::string fixed_frame
fixed frame
Definition: convert.h:83
dictionary calibration
#define ROS_ERROR_STREAM(args)
ros::Subscriber velodyne_scan_
Definition: convert.h:72
boost::shared_ptr< dynamic_reconfigure::Server< velodyne_pointcloud::CloudNodeConfig > > srv_
Definition: convert.h:69


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