transform.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 
22 
25 
26 namespace velodyne_pointcloud
27 {
30  tf_prefix_(tf::getPrefixParam(private_nh)),
31  data_(new velodyne_rawdata::RawData),
32  first_rcfg_call(true)
33  {
34  boost::optional<velodyne_pointcloud::Calibration> calibration = data_->setup(private_nh);
35  if(calibration)
36  {
37  ROS_DEBUG_STREAM("Calibration file loaded.");
38  config_.num_lasers = static_cast<uint16_t>(calibration.get().num_lasers);
39  }
40  else
41  {
42  ROS_ERROR_STREAM("Could not load calibration file!");
43  }
44 
45  config_.target_frame = config_.fixed_frame = "velodyne";
46  tf_ptr_ = boost::make_shared<tf::TransformListener>();
47 
49  {
52  config_.num_lasers, data_->scansPerPacket(), tf_ptr_));
53  }
54  else
55  {
59  data_->scansPerPacket(), tf_ptr_));
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<TransformNodeCfg>> (private_nh);
67  dynamic_reconfigure::Server<TransformNodeCfg>::CallbackType f;
68  f = boost::bind (&Transform::reconfigure_callback, this, _1, _2);
69  srv_->setCallback (f);
70 
71  // subscribe to VelodyneScan packets using transform filter
72  velodyne_scan_.subscribe(node, "velodyne_packets", 10);
75  tf_filter_ptr_->registerCallback(boost::bind(&Transform::processScan, this, _1));
76  private_nh.param<std::string>("fixed_frame", config_.fixed_frame, "odom");
77 
78  // Diagnostics
79  diagnostics_.setHardwareID("Velodyne Transform");
80  // Arbitrary frequencies since we don't know which RPM is used, and are only
81  // concerned about monitoring the frequency.
82  diag_min_freq_ = 2.0;
83  diag_max_freq_ = 20.0;
84  using namespace diagnostic_updater;
85  diag_topic_.reset(new TopicDiagnostic("velodyne_points", diagnostics_,
88  0.1, 10),
90 
91  }
92 
94  velodyne_pointcloud::TransformNodeConfig &config, uint32_t level)
95  {
96  ROS_INFO_STREAM("Reconfigure request.");
97  data_->setParameters(config.min_range, config.max_range,
98  config.view_direction, config.view_width);
99  config_.target_frame = tf::resolve(tf_prefix_, config.frame_id);
100  ROS_INFO_STREAM("Target frame ID now: " << config_.target_frame);
101  config_.min_range = config.min_range;
102  config_.max_range = config.max_range;
103 
104  boost::lock_guard<boost::mutex> guard(reconfigure_mtx_);
105 
106  if(first_rcfg_call || config.organize_cloud != config_.organize_cloud){
107  first_rcfg_call = false;
108  config_.organize_cloud = config.organize_cloud;
110  {
111  ROS_INFO_STREAM("Using the organized cloud format...");
115  config_.num_lasers, data_->scansPerPacket()));
116  }
117  else
118  {
122  data_->scansPerPacket()));
123  }
124  }
126  }
127 
133  void
134  Transform::processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
135  {
136  if (output_.getNumSubscribers() == 0) // no one listening?
137  return; // avoid much work
138 
139  boost::lock_guard<boost::mutex> guard(reconfigure_mtx_);
140 
141  // allocate a point cloud with same time and frame ID as raw data
142  container_ptr->setup(scanMsg);
143 
144  // process each packet provided by the driver
145  for (size_t i = 0; i < scanMsg->packets.size(); ++i)
146  {
147  container_ptr->computeTransformation(scanMsg->packets[i].stamp);
148  data_->unpack(scanMsg->packets[i], *container_ptr);
149  }
150  // publish the accumulated cloud message
151  output_.publish(container_ptr->finishCloud());
152 
153  diag_topic_->tick(scanMsg->header.stamp);
155  }
156 
157 } // namespace velodyne_pointcloud
double min_range
minimum range to publish
Definition: transform.h:90
boost::shared_ptr< tf::TransformListener > tf_ptr_
Definition: transform.h:81
boost::shared_ptr< dynamic_reconfigure::Server< velodyne_pointcloud::TransformNodeConfig > > srv_
Definition: transform.h:73
boost::shared_ptr< tf::MessageFilter< velodyne_msgs::VelodyneScan > > tf_filter_ptr_
Definition: transform.h:80
message_filters::Subscriber< velodyne_msgs::VelodyneScan > velodyne_scan_
Definition: transform.h:78
void publish(const boost::shared_ptr< M > &message) const
std::string getPrefixParam(ros::NodeHandle &nh)
void setHardwareID(const std::string &hwid)
std::string fixed_frame
fixed frame
Definition: transform.h:87
diagnostic_updater::Updater diagnostics_
Definition: transform.h:101
bool organize_cloud
enable/disable organized cloud structure
Definition: transform.h:88
std::string resolve(const std::string &prefix, const std::string &frame_name)
boost::shared_ptr< velodyne_rawdata::RawData > data_
Definition: transform.h:77
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::string target_frame
target frame
Definition: transform.h:86
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void reconfigure_callback(velodyne_pointcloud::TransformNodeConfig &config, uint32_t level)
Definition: transform.cc:93
#define ROS_DEBUG_STREAM(args)
const std::string tf_prefix_
Definition: transform.h:76
uint32_t getNumSubscribers() const
#define ROS_INFO_STREAM(args)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > diag_topic_
Definition: transform.h:104
double max_range
maximum range to publish
Definition: transform.h:89
void processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
Callback for raw scan messages.
Definition: transform.cc:134
dictionary calibration
#define ROS_ERROR_STREAM(args)
uint16_t num_lasers
number of lasers
Definition: transform.h:91
boost::shared_ptr< velodyne_rawdata::DataContainerBase > container_ptr
Definition: transform.h:98
Transform(ros::NodeHandle node, ros::NodeHandle private_nh)
Constructor.
Definition: transform.cc:29


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