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 {
29  Transform::Transform(ros::NodeHandle node, ros::NodeHandle private_nh, std::string const & node_name):
30  data_(new velodyne_rawdata::RawData),
31  first_rcfg_call(true),
32  diagnostics_(node, private_nh, node_name)
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  // advertise output point cloud (before subscribing to input data)
46  output_ = node.advertise<sensor_msgs::PointCloud2>("velodyne_points", 10);
47 
48  srv_ = boost::make_shared<dynamic_reconfigure::Server<TransformNodeCfg>> (private_nh);
49  dynamic_reconfigure::Server<TransformNodeCfg>::CallbackType f;
50  f = boost::bind (&Transform::reconfigure_callback, this, _1, _2);
51  srv_->setCallback (f);
52 
53  velodyne_scan_ = node.subscribe("velodyne_packets", 10, &Transform::processScan, this);
54 
55  // Diagnostics
56  diagnostics_.setHardwareID("Velodyne Transform");
57  // Arbitrary frequencies since we don't know which RPM is used, and are only
58  // concerned about monitoring the frequency.
59  diag_min_freq_ = 2.0;
60  diag_max_freq_ = 20.0;
61  using namespace diagnostic_updater;
62  diag_topic_.reset(new TopicDiagnostic("velodyne_points", diagnostics_,
65  0.1, 10),
67 
68  }
69 
71  velodyne_pointcloud::TransformNodeConfig &config, uint32_t level)
72  {
73  ROS_INFO_STREAM("Reconfigure request.");
74  data_->setParameters(config.min_range, config.max_range,
75  config.view_direction, config.view_width);
76  config_.target_frame = config.target_frame;
77  config_.fixed_frame = config.fixed_frame;
78  ROS_INFO_STREAM("Target frame ID now: " << config_.target_frame);
79  ROS_INFO_STREAM("Fixed frame ID now: " << config_.fixed_frame);
80  config_.min_range = config.min_range;
81  config_.max_range = config.max_range;
82 
83  boost::lock_guard<boost::mutex> guard(reconfigure_mtx_);
84 
85  if(first_rcfg_call || config.organize_cloud != config_.organize_cloud){
86  first_rcfg_call = false;
87  config_.organize_cloud = config.organize_cloud;
89  {
90  ROS_INFO_STREAM("Using the organized cloud format...");
94  config_.num_lasers, data_->scansPerPacket()));
95  }
96  else
97  {
101  data_->scansPerPacket()));
102  }
103  }
105  }
106 
112  void
113  Transform::processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
114  {
115  if (output_.getNumSubscribers() == 0) // no one listening?
116  return; // avoid much work
117 
118  boost::lock_guard<boost::mutex> guard(reconfigure_mtx_);
119 
120  // allocate a point cloud with same time and frame ID as raw data
121  container_ptr->setup(scanMsg);
122 
123  // sufficient to calculate single transform for whole scan
124  if(!container_ptr->computeTransformToTarget(scanMsg->header.stamp))
125  {
126  // target frame not available
127  return;
128  }
129 
130  // process each packet provided by the driver
131  for (size_t i = 0; i < scanMsg->packets.size(); ++i)
132  {
133  // calculate individual transform for each packet to account for ego
134  // during one rotation of the velodyne sensor
135  if(!container_ptr->computeTransformToFixed(scanMsg->packets[i].stamp))
136  {
137  // fixed frame not available
138  return;
139  }
140  data_->unpack(scanMsg->packets[i], *container_ptr, scanMsg->header.stamp);
141  }
142  // publish the accumulated cloud message
143  output_.publish(container_ptr->finishCloud());
144 
145  diag_topic_->tick(scanMsg->header.stamp);
147  }
148 
149 } // namespace velodyne_pointcloud
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_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr
diagnostic_updater::TimeStampStatusParam
velodyne_pointcloud::Transform::Config::num_lasers
uint16_t num_lasers
number of lasers
Definition: transform.h:91
velodyne_pointcloud::Transform::processScan
void processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
Callback for raw scan messages.
Definition: transform.cc:113
add_two_pt.calibration
calibration
Definition: add_two_pt.py:14
velodyne_pointcloud::Transform::diag_max_freq_
double diag_max_freq_
Definition: transform.h:103
velodyne_pointcloud::Transform::velodyne_scan_
ros::Subscriber velodyne_scan_
Definition: transform.h:80
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
organized_cloudXYZIRT.h
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
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
diagnostic_updater
velodyne_pointcloud::PointcloudXYZIRT
Definition: pointcloudXYZIRT.h:41
velodyne_rawdata
Definition: datacontainerbase.h:45
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
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
diagnostic_updater::Updater::setHardwareID
void setHardwareID(const std::string &hwid)
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
diagnostic_updater::TopicDiagnostic
diagnostic_updater::Updater::update
void update()
velodyne_pointcloud::Transform::config_
Config config_
Definition: transform.h:94
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
transform.h
velodyne_pointcloud::Transform::diag_min_freq_
double diag_min_freq_
Definition: transform.h:102
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
velodyne_pointcloud::OrganizedCloudXYZIRT
Definition: organized_cloudXYZIRT.h:42
velodyne_pointcloud::Transform::data_
boost::shared_ptr< velodyne_rawdata::RawData > data_
Definition: transform.h:79
ros::NodeHandle
gen_calibration.f
f
Definition: gen_calibration.py:213
diagnostic_updater::FrequencyStatusParam


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Sun Jun 2 2024 02:29:13