driver.cc
Go to the documentation of this file.
1 // Copyright (C) 2007, 2009-2012 Austin Robot Technology, Patrick Beeson, Jack O'Quin
2 // 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 
38 #include <string>
39 #include <cmath>
40 
41 #include <ros/ros.h>
42 #include <tf/transform_listener.h>
43 #include <velodyne_msgs/VelodyneScan.h>
44 
45 #include "velodyne_driver/driver.h"
46 
47 namespace velodyne_driver
48 {
49 
51  ros::NodeHandle private_nh,
52  std::string const & node_name)
53  : diagnostics_(node, private_nh, node_name)
54 {
55  // use private node handle to get parameters
56  private_nh.param("frame_id", config_.frame_id, std::string("velodyne"));
57  std::string tf_prefix = tf::getPrefixParam(private_nh);
58  ROS_DEBUG_STREAM("tf_prefix: " << tf_prefix);
59  config_.frame_id = tf::resolve(tf_prefix, config_.frame_id);
60 
61  // get model name, validate string, determine packet rate
62  private_nh.param("model", config_.model, std::string("64E"));
63  double packet_rate; // packet frequency (Hz)
64  std::string model_full_name;
65  if ((config_.model == "VLS128") )
66  {
67  packet_rate = 6253.9; // 3 firing cycles in a data packet. 3 x 53.3 μs = 0.1599 ms is the accumulation delay per packet.
68  // 1 packet/0.1599 ms = 6253.9 packets/second
69 
70  model_full_name = config_.model;
71  }
72  else if ((config_.model == "64E_S2") ||
73  (config_.model == "64E_S2.1")) // generates 1333312 points per second
74  { // 1 packet holds 384 points
75  packet_rate = 3472.17; // 1333312 / 384
76  model_full_name = std::string("HDL-") + config_.model;
77  }
78  else if (config_.model == "64E")
79  {
80  packet_rate = 2600.0;
81  model_full_name = std::string("HDL-") + config_.model;
82  }
83  else if (config_.model == "64E_S3") // generates 2222220 points per second (half for strongest and half for lastest)
84  { // 1 packet holds 384 points
85  packet_rate = 5787.03; // 2222220 / 384
86  model_full_name = std::string("HDL-") + config_.model;
87  }
88  else if (config_.model == "32E")
89  {
90  packet_rate = 1808.0;
91  model_full_name = std::string("HDL-") + config_.model;
92  }
93  else if (config_.model == "32C")
94  {
95  packet_rate = 1507.0;
96  model_full_name = std::string("VLP-") + config_.model;
97  }
98  else if (config_.model == "VLP16")
99  {
100  packet_rate = 754; // 754 Packets/Second for Last or Strongest mode 1508 for dual (VLP-16 User Manual)
101  model_full_name = "VLP-16";
102  }
103  else
104  {
105  ROS_ERROR_STREAM("unknown Velodyne LIDAR model: " << config_.model);
106  packet_rate = 2600.0;
107  }
108  std::string deviceName(std::string("Velodyne ") + model_full_name);
109 
110  private_nh.param("rpm", config_.rpm, 600.0);
111  ROS_INFO_STREAM(deviceName << " rotating at " << config_.rpm << " RPM");
112  double frequency = (config_.rpm / 60.0); // expected Hz rate
113 
114  // default number of packets for each scan is a single revolution
115  // (fractions rounded up)
116  config_.npackets = (int) ceil(packet_rate / frequency);
117  private_nh.getParam("npackets", config_.npackets);
118  ROS_INFO_STREAM("publishing " << config_.npackets << " packets per scan");
119 
120  // if we are timestamping based on the first or last packet in the scan
121  private_nh.param("timestamp_first_packet", config_.timestamp_first_packet, false);
122  if (config_.timestamp_first_packet)
123  ROS_INFO("Setting velodyne scan start time to timestamp of first packet");
124 
125  std::string dump_file;
126  private_nh.param("pcap", dump_file, std::string(""));
127 
128  double cut_angle;
129  private_nh.param("cut_angle", cut_angle, -0.01);
130  if (cut_angle < 0.0)
131  {
132  ROS_INFO_STREAM("Cut at specific angle feature deactivated.");
133  }
134  else if (cut_angle < (2*M_PI))
135  {
136  ROS_INFO_STREAM("Cut at specific angle feature activated. "
137  "Cutting velodyne points always at " << cut_angle << " rad.");
138  }
139  else
140  {
141  ROS_ERROR_STREAM("cut_angle parameter is out of range. Allowed range is "
142  << "between 0.0 and 2*PI or negative values to deactivate this feature.");
143  cut_angle = -0.01;
144  }
145 
146  // Convert cut_angle from radian to one-hundredth degree,
147  // which is used in velodyne packets
148  config_.cut_angle = int((cut_angle*360/(2*M_PI))*100);
149 
150  int udp_port;
151  private_nh.param("port", udp_port, (int) DATA_PORT_NUMBER);
152 
153  // Initialize dynamic reconfigure
154  srv_ = boost::make_shared <dynamic_reconfigure::Server<velodyne_driver::
155  VelodyneNodeConfig> > (private_nh);
156  dynamic_reconfigure::Server<velodyne_driver::VelodyneNodeConfig>::
157  CallbackType f;
158  f = boost::bind (&VelodyneDriver::callback, this, _1, _2);
159  srv_->setCallback (f); // Set callback function und call initially
160 
161  // initialize diagnostics
162  diagnostics_.setHardwareID(deviceName);
163  const double diag_freq = packet_rate/config_.npackets;
164  diag_max_freq_ = diag_freq;
165  diag_min_freq_ = diag_freq;
166  ROS_INFO("expected frequency: %.3f (Hz)", diag_freq);
167 
168  double diagnostic_frequency_tolerance;
169  private_nh.param("diagnostic_frequency_tolerance", diagnostic_frequency_tolerance, 0.1);
170  using namespace diagnostic_updater;
171  diag_topic_.reset(new TopicDiagnostic("velodyne_packets", diagnostics_,
174  diagnostic_frequency_tolerance, 10),
177 
178  config_.enabled = true;
179 
180  // open Velodyne input device or file
181  if (dump_file != "") // have PCAP file?
182  {
183  // read data from packet capture file
184  input_.reset(new velodyne_driver::InputPCAP(private_nh, udp_port,
185  packet_rate, dump_file));
186  }
187  else
188  {
189  // read data from live socket
190  input_.reset(new velodyne_driver::InputSocket(private_nh, udp_port));
191  }
192 
193  // raw packet output topic
194  output_ =
195  node.advertise<velodyne_msgs::VelodyneScan>("velodyne_packets", 10);
196 
197  last_azimuth_ = -1;
198 }
199 
205 {
206  if (!config_.enabled) {
207  // If we are not enabled exit once a second to let the caller handle
208  // anything it might need to, such as if it needs to exit.
209  ros::Duration(1).sleep();
210  return true;
211  }
212 
213  // Allocate a new shared pointer for zero-copy sharing with other nodelets.
214  velodyne_msgs::VelodyneScanPtr scan(new velodyne_msgs::VelodyneScan);
215 
216  if( config_.cut_angle >= 0) //Cut at specific angle feature enabled
217  {
218  scan->packets.reserve(config_.npackets);
219  velodyne_msgs::VelodynePacket tmp_packet;
220  while(true)
221  {
222  while(true)
223  {
224  int rc = input_->getPacket(&tmp_packet, config_.time_offset);
225  if (rc == 1) break; // got a full packet?
226  if (rc < 0) return false; // end of file reached?
227  if (rc == 0) continue; //timeout?
228  }
229  scan->packets.push_back(tmp_packet);
230 
231  // Extract base rotation of first block in packet
232  std::size_t azimuth_data_pos = 100*0+2;
233  int azimuth = *( (u_int16_t*) (&tmp_packet.data[azimuth_data_pos]));
234 
235  //if first packet in scan, there is no "valid" last_azimuth_
236  if (last_azimuth_ == -1) {
237  last_azimuth_ = azimuth;
238  continue;
239  }
240  if((last_azimuth_ < config_.cut_angle && config_.cut_angle <= azimuth)
241  || ( config_.cut_angle <= azimuth && azimuth < last_azimuth_)
242  || (azimuth < last_azimuth_ && last_azimuth_ < config_.cut_angle))
243  {
244  last_azimuth_ = azimuth;
245  break; // Cut angle passed, one full revolution collected
246  }
247  last_azimuth_ = azimuth;
248  }
249  }
250  else // standard behaviour
251  {
252  // Since the velodyne delivers data at a very high rate, keep
253  // reading and publishing scans as fast as possible.
254  scan->packets.resize(config_.npackets);
255  for (int i = 0; i < config_.npackets; ++i)
256  {
257  while (true)
258  {
259  // keep reading until full packet received
260  int rc = input_->getPacket(&scan->packets[i], config_.time_offset);
261  if (rc == 1) break; // got a full packet?
262  if (rc < 0) return false; // end of file reached?
263  if (rc == 0) continue; //timeout?
264  }
265  }
266  }
267 
268  // publish message using time of last packet read
269  ROS_DEBUG("Publishing a full Velodyne scan.");
270  if (config_.timestamp_first_packet){
271  scan->header.stamp = scan->packets.front().stamp;
272  }
273  else{
274  scan->header.stamp = scan->packets.back().stamp;
275  }
276  scan->header.frame_id = config_.frame_id;
277  output_.publish(scan);
278 
279  // notify diagnostics that a message has been published, updating
280  // its status
281  diag_topic_->tick(scan->header.stamp);
283 
284  return true;
285 }
286 
287 void VelodyneDriver::callback(velodyne_driver::VelodyneNodeConfig &config,
288  uint32_t level)
289 {
290  ROS_INFO("Reconfigure Request");
291  if (level & 1)
292  {
293  config_.time_offset = config.time_offset;
294  }
295  if (level & 2)
296  {
297  config_.enabled = config.enabled;
298  }
299 }
300 
302 {
303  (void)event;
304  // Call necessary to provide an error when no velodyne packets are received
306 }
307 
308 } // namespace velodyne_driver
velodyne_driver::VelodyneDriver::callback
void callback(velodyne_driver::VelodyneNodeConfig &config, uint32_t level)
Definition: driver.cc:287
velodyne_driver::VelodyneDriver::diag_timer_
ros::Timer diag_timer_
Definition: driver.h:88
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
diagnostic_updater::TimeStampStatusParam
driver.h
velodyne_driver::InputSocket
Live Velodyne input from socket.
Definition: input.h:97
velodyne_driver::VelodyneDriver::srv_
boost::shared_ptr< dynamic_reconfigure::Server< velodyne_driver::VelodyneNodeConfig > > srv_
Definition: driver.h:67
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
velodyne_driver::VelodyneDriver::output_
ros::Publisher output_
Definition: driver.h:84
tf::resolve
std::string resolve(const std::string &prefix, const std::string &frame_name)
velodyne_driver::VelodyneDriver::diag_topic_
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > diag_topic_
Definition: driver.h:92
velodyne_driver::VelodyneDriver::cut_angle
int cut_angle
Definition: driver.h:76
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
f
f
velodyne_driver::VelodyneDriver::VelodyneDriver
VelodyneDriver(ros::NodeHandle node, ros::NodeHandle private_nh, std::string const &node_name=ros::this_node::getName())
Definition: driver.cc:50
velodyne_driver::VelodyneDriver::diagnostics_
diagnostic_updater::Updater diagnostics_
Definition: driver.h:89
velodyne_driver::VelodyneDriver::poll
bool poll(void)
Definition: driver.cc:204
ROS_DEBUG
#define ROS_DEBUG(...)
tf::getPrefixParam
std::string getPrefixParam(ros::NodeHandle &nh)
diagnostic_updater
velodyne_driver::VelodyneDriver::diag_min_freq_
double diag_min_freq_
Definition: driver.h:90
velodyne_driver::DATA_PORT_NUMBER
static uint16_t DATA_PORT_NUMBER
Definition: input.h:68
velodyne_driver::VelodyneDriver::input_
boost::shared_ptr< Input > input_
Definition: driver.h:83
ros::TimerEvent
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
diagnostic_updater::Updater::setHardwareID
void setHardwareID(const std::string &hwid)
velodyne_driver::VelodyneDriver::diagTimerCallback
void diagTimerCallback(const ros::TimerEvent &event)
Definition: driver.cc:301
velodyne_driver::VelodyneDriver::diag_max_freq_
double diag_max_freq_
Definition: driver.h:91
transform_listener.h
diagnostic_updater::TopicDiagnostic
diagnostic_updater::Updater::update
void update()
velodyne_driver::VelodyneDriver::last_azimuth_
int last_azimuth_
Definition: driver.h:85
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::Duration::sleep
bool sleep() const
velodyne_driver
Definition: driver.h:45
ROS_INFO
#define ROS_INFO(...)
velodyne_driver::InputPCAP
Velodyne input from PCAP dump file.
Definition: input.h:119
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
velodyne_driver::VelodyneDriver::config_
struct velodyne_driver::VelodyneDriver::@0 config_
ros::NodeHandle
diagnostic_updater::FrequencyStatusParam


velodyne_driver
Author(s): Jack O'Quin, Patrick Beeson, Michael Quinlan, Yaxin Liu
autogenerated on Tue May 2 2023 02:28:00