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


velodyne_driver
Author(s): Jack O'Quin, Patrick Beeson, Michael Quinlan, Yaxin Liu
autogenerated on Thu Jul 4 2019 19:09:28