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


velodyne_driver
Author(s): Jack O'Quin, Patrick Beeson, Michael Quinlan, Yaxin Liu
autogenerated on Sun Sep 6 2020 03:25:28