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 {
25  data_(new velodyne_rawdata::RawData()), first_rcfg_call(true)
26  {
27 
28  boost::optional<velodyne_pointcloud::Calibration> calibration = data_->setup(private_nh);
29  if(calibration)
30  {
31  ROS_DEBUG_STREAM("Calibration file loaded.");
32  config_.num_lasers = static_cast<uint16_t>(calibration.get().num_lasers);
33  }
34  else
35  {
36  ROS_ERROR_STREAM("Could not load calibration file!");
37  }
38 
40  {
44  config_.num_lasers, data_->scansPerPacket()));
45  }
46  else
47  {
51  data_->scansPerPacket()));
52  }
53 
54 
55  // advertise output point cloud (before subscribing to input data)
56  output_ =
57  node.advertise<sensor_msgs::PointCloud2>("velodyne_points", 10);
58 
59  srv_ = boost::make_shared <dynamic_reconfigure::Server<velodyne_pointcloud::
60  CloudNodeConfig> > (private_nh);
61  dynamic_reconfigure::Server<velodyne_pointcloud::CloudNodeConfig>::
62  CallbackType f;
63  f = boost::bind (&Convert::callback, this, _1, _2);
64  srv_->setCallback (f);
65 
66  // subscribe to VelodyneScan packets
68  node.subscribe("velodyne_packets", 10,
69  &Convert::processScan, (Convert *) this,
70  ros::TransportHints().tcpNoDelay(true));
71 
72  // Diagnostics
73  diagnostics_.setHardwareID("Velodyne Convert");
74  // Arbitrary frequencies since we don't know which RPM is used, and are only
75  // concerned about monitoring the frequency.
76  diag_min_freq_ = 2.0;
77  diag_max_freq_ = 20.0;
78  using namespace diagnostic_updater;
79  diag_topic_.reset(new TopicDiagnostic("velodyne_points", diagnostics_,
82  0.1, 10),
84  }
85 
86  void Convert::callback(velodyne_pointcloud::CloudNodeConfig &config,
87  uint32_t level)
88  {
89  ROS_INFO("Reconfigure Request");
90  data_->setParameters(config.min_range, config.max_range, config.view_direction,
91  config.view_width);
92  config_.fixed_frame = config.fixed_frame;
93  config_.target_frame = config.target_frame;
94  config_.min_range = config.min_range;
95  config_.max_range = config.max_range;
96 
97  if(first_rcfg_call || config.organize_cloud != config_.organize_cloud){
98  first_rcfg_call = false;
99  config_.organize_cloud = config.organize_cloud;
100  if(config_.organize_cloud) // TODO only on change
101  {
102  ROS_INFO_STREAM("Using the organized cloud format...");
106  config_.num_lasers, data_->scansPerPacket()));
107  }
108  else
109  {
113  data_->scansPerPacket()));
114  }
115  }
116 
118 
119  }
120 
122  void Convert::processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
123  {
124  if (output_.getNumSubscribers() == 0) // no one listening?
125  return; // avoid much work
126 
127  boost::lock_guard<boost::mutex> guard(reconfigure_mtx_);
128  // allocate a point cloud with same time and frame ID as raw data
129  container_ptr_->setup(scanMsg);
130 
131  // process each packet provided by the driver
132  for (size_t i = 0; i < scanMsg->packets.size(); ++i)
133  {
134  data_->unpack(scanMsg->packets[i], *container_ptr_);
135  }
136 
137  // publish the accumulated cloud message
138  diag_topic_->tick(scanMsg->header.stamp);
140  output_.publish(container_ptr_->finishCloud());
141  }
142 
143 } // namespace velodyne_pointcloud
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
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher output_
Definition: convert.h:70
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:82
void setHardwareID(const std::string &hwid)
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
#define ROS_INFO(...)
Convert(ros::NodeHandle node, ros::NodeHandle private_nh)
Constructor.
Definition: convert.cc:24
diagnostic_updater::Updater diagnostics_
Definition: convert.h:92
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:68
std::string fixed_frame
fixed frame
Definition: convert.h:80
dictionary calibration
#define ROS_ERROR_STREAM(args)
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