driver.cc
Go to the documentation of this file.
00001 // Copyright (C) 2007, 2009-2012 Austin Robot Technology, Patrick Beeson, Jack O'Quin
00002 // All rights reserved.
00003 //
00004 // Software License Agreement (BSD License 2.0)
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions
00008 // are met:
00009 //
00010 //  * Redistributions of source code must retain the above copyright
00011 //    notice, this list of conditions and the following disclaimer.
00012 //  * Redistributions in binary form must reproduce the above
00013 //    copyright notice, this list of conditions and the following
00014 //    disclaimer in the documentation and/or other materials provided
00015 //    with the distribution.
00016 //  * Neither the name of {copyright_holder} nor the names of its
00017 //    contributors may be used to endorse or promote products derived
00018 //    from this software without specific prior written permission.
00019 //
00020 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 // POSSIBILITY OF SUCH DAMAGE.
00032 
00038 #include <string>
00039 #include <cmath>
00040 
00041 #include <ros/ros.h>
00042 #include <tf/transform_listener.h>
00043 #include <velodyne_msgs/VelodyneScan.h>
00044 
00045 #include "velodyne_driver/driver.h"
00046 
00047 namespace velodyne_driver
00048 {
00049 
00050 VelodyneDriver::VelodyneDriver(ros::NodeHandle node,
00051                                ros::NodeHandle private_nh)
00052 {
00053   // use private node handle to get parameters
00054   private_nh.param("frame_id", config_.frame_id, std::string("velodyne"));
00055   std::string tf_prefix = tf::getPrefixParam(private_nh);
00056   ROS_DEBUG_STREAM("tf_prefix: " << tf_prefix);
00057   config_.frame_id = tf::resolve(tf_prefix, config_.frame_id);
00058 
00059   // get model name, validate string, determine packet rate
00060   private_nh.param("model", config_.model, std::string("64E"));
00061   double packet_rate;                   // packet frequency (Hz)
00062   std::string model_full_name;
00063   if ((config_.model == "64E_S2") || 
00064       (config_.model == "64E_S2.1"))    // generates 1333312 points per second
00065     {                                   // 1 packet holds 384 points
00066       packet_rate = 3472.17;            // 1333312 / 384
00067       model_full_name = std::string("HDL-") + config_.model;
00068     }
00069   else if (config_.model == "64E")
00070     {
00071       packet_rate = 2600.0;
00072       model_full_name = std::string("HDL-") + config_.model;
00073     }
00074   else if (config_.model == "64E_S3") // generates 2222220 points per second (half for strongest and half for lastest)
00075     {                                 // 1 packet holds 384 points
00076       packet_rate = 5787.03;          // 2222220 / 384
00077       model_full_name = std::string("HDL-") + config_.model;
00078     }
00079   else if (config_.model == "32E")
00080     {
00081       packet_rate = 1808.0;
00082       model_full_name = std::string("HDL-") + config_.model;
00083     }
00084     else if (config_.model == "32C")
00085     {
00086       packet_rate = 1507.0;
00087       model_full_name = std::string("VLP-") + config_.model;
00088     }
00089   else if (config_.model == "VLP16")
00090     {
00091       packet_rate = 754;             // 754 Packets/Second for Last or Strongest mode 1508 for dual (VLP-16 User Manual)
00092       model_full_name = "VLP-16";
00093     }
00094   else
00095     {
00096       ROS_ERROR_STREAM("unknown Velodyne LIDAR model: " << config_.model);
00097       packet_rate = 2600.0;
00098     }
00099   std::string deviceName(std::string("Velodyne ") + model_full_name);
00100 
00101   private_nh.param("rpm", config_.rpm, 600.0);
00102   ROS_INFO_STREAM(deviceName << " rotating at " << config_.rpm << " RPM");
00103   double frequency = (config_.rpm / 60.0);     // expected Hz rate
00104 
00105   // default number of packets for each scan is a single revolution
00106   // (fractions rounded up)
00107   config_.npackets = (int) ceil(packet_rate / frequency);
00108   private_nh.getParam("npackets", config_.npackets);
00109   ROS_INFO_STREAM("publishing " << config_.npackets << " packets per scan");
00110 
00111   std::string dump_file;
00112   private_nh.param("pcap", dump_file, std::string(""));
00113 
00114   double cut_angle;
00115   private_nh.param("cut_angle", cut_angle, -0.01);
00116   if (cut_angle < 0.0)
00117   {
00118     ROS_INFO_STREAM("Cut at specific angle feature deactivated.");
00119   }
00120   else if (cut_angle < (2*M_PI))
00121   {
00122       ROS_INFO_STREAM("Cut at specific angle feature activated. " 
00123         "Cutting velodyne points always at " << cut_angle << " rad.");
00124   }
00125   else
00126   {
00127     ROS_ERROR_STREAM("cut_angle parameter is out of range. Allowed range is "
00128     << "between 0.0 and 2*PI or negative values to deactivate this feature.");
00129     cut_angle = -0.01;
00130   }
00131 
00132   // Convert cut_angle from radian to one-hundredth degree, 
00133   // which is used in velodyne packets
00134   config_.cut_angle = int((cut_angle*360/(2*M_PI))*100);
00135 
00136   int udp_port;
00137   private_nh.param("port", udp_port, (int) DATA_PORT_NUMBER);
00138 
00139   // Initialize dynamic reconfigure
00140   srv_ = boost::make_shared <dynamic_reconfigure::Server<velodyne_driver::
00141     VelodyneNodeConfig> > (private_nh);
00142   dynamic_reconfigure::Server<velodyne_driver::VelodyneNodeConfig>::
00143     CallbackType f;
00144   f = boost::bind (&VelodyneDriver::callback, this, _1, _2);
00145   srv_->setCallback (f); // Set callback function und call initially
00146 
00147   // initialize diagnostics
00148   diagnostics_.setHardwareID(deviceName);
00149   const double diag_freq = packet_rate/config_.npackets;
00150   diag_max_freq_ = diag_freq;
00151   diag_min_freq_ = diag_freq;
00152   ROS_INFO("expected frequency: %.3f (Hz)", diag_freq);
00153 
00154   using namespace diagnostic_updater;
00155   diag_topic_.reset(new TopicDiagnostic("velodyne_packets", diagnostics_,
00156                                         FrequencyStatusParam(&diag_min_freq_,
00157                                                              &diag_max_freq_,
00158                                                              0.1, 10),
00159                                         TimeStampStatusParam()));
00160   diag_timer_ = private_nh.createTimer(ros::Duration(0.2), &VelodyneDriver::diagTimerCallback,this);
00161 
00162   config_.enabled = true;
00163 
00164   // open Velodyne input device or file
00165   if (dump_file != "")                  // have PCAP file?
00166     {
00167       // read data from packet capture file
00168       input_.reset(new velodyne_driver::InputPCAP(private_nh, udp_port,
00169                                                   packet_rate, dump_file));
00170     }
00171   else
00172     {
00173       // read data from live socket
00174       input_.reset(new velodyne_driver::InputSocket(private_nh, udp_port));
00175     }
00176 
00177   // raw packet output topic
00178   output_ =
00179     node.advertise<velodyne_msgs::VelodyneScan>("velodyne_packets", 10);
00180 
00181   last_azimuth_ = -1;
00182 }
00183 
00188 bool VelodyneDriver::poll(void)
00189 {
00190   if (!config_.enabled) {
00191     // If we are not enabled exit once a second to let the caller handle
00192     // anything it might need to, such as if it needs to exit.
00193     ros::Duration(1).sleep();
00194     return true;
00195   }
00196 
00197   // Allocate a new shared pointer for zero-copy sharing with other nodelets.
00198   velodyne_msgs::VelodyneScanPtr scan(new velodyne_msgs::VelodyneScan);
00199 
00200   if( config_.cut_angle >= 0) //Cut at specific angle feature enabled
00201   {
00202     scan->packets.reserve(config_.npackets);
00203     velodyne_msgs::VelodynePacket tmp_packet;
00204     while(true)
00205     {
00206       while(true)
00207       {
00208         int rc = input_->getPacket(&tmp_packet, config_.time_offset);
00209         if (rc == 0) break;       // got a full packet?
00210         if (rc < 0) return false; // end of file reached?
00211       }
00212       scan->packets.push_back(tmp_packet);
00213 
00214       // Extract base rotation of first block in packet
00215       std::size_t azimuth_data_pos = 100*0+2;
00216       int azimuth = *( (u_int16_t*) (&tmp_packet.data[azimuth_data_pos]));
00217 
00218       //if first packet in scan, there is no "valid" last_azimuth_
00219       if (last_azimuth_ == -1) {
00220          last_azimuth_ = azimuth;
00221          continue;
00222       }
00223       if((last_azimuth_ < config_.cut_angle && config_.cut_angle <= azimuth)
00224          || ( config_.cut_angle <= azimuth && azimuth < last_azimuth_)
00225          || (azimuth < last_azimuth_ && last_azimuth_ < config_.cut_angle))
00226       {
00227         last_azimuth_ = azimuth;
00228         break; // Cut angle passed, one full revolution collected
00229       }
00230       last_azimuth_ = azimuth;
00231     }
00232   }
00233   else // standard behaviour
00234   {
00235   // Since the velodyne delivers data at a very high rate, keep
00236   // reading and publishing scans as fast as possible.
00237     scan->packets.resize(config_.npackets);
00238     for (int i = 0; i < config_.npackets; ++i)
00239     {
00240       while (true)
00241         {
00242           // keep reading until full packet received
00243           int rc = input_->getPacket(&scan->packets[i], config_.time_offset);
00244           if (rc == 0) break;       // got a full packet?
00245           if (rc < 0) return false; // end of file reached?
00246         }
00247     }
00248   }
00249 
00250   // publish message using time of last packet read
00251   ROS_DEBUG("Publishing a full Velodyne scan.");
00252   scan->header.stamp = scan->packets.back().stamp;
00253   scan->header.frame_id = config_.frame_id;
00254   output_.publish(scan);
00255 
00256   // notify diagnostics that a message has been published, updating
00257   // its status
00258   diag_topic_->tick(scan->header.stamp);
00259   diagnostics_.update();
00260 
00261   return true;
00262 }
00263 
00264 void VelodyneDriver::callback(velodyne_driver::VelodyneNodeConfig &config,
00265               uint32_t level)
00266 {
00267   ROS_INFO("Reconfigure Request");
00268   if (level & 1)
00269   {
00270     config_.time_offset = config.time_offset;
00271   }
00272   if (level & 2)
00273   {
00274     config_.enabled = config.enabled;
00275   }
00276 }
00277 
00278 void VelodyneDriver::diagTimerCallback(const ros::TimerEvent &event)
00279 {
00280   (void)event;
00281   // Call necessary to provide an error when no velodyne packets are received
00282   diagnostics_.update();
00283 }
00284 
00285 } // namespace velodyne_driver


velodyne_driver
Author(s): Jack O'Quin, Patrick Beeson, Michael Quinlan, Yaxin Liu
autogenerated on Wed Jul 3 2019 19:32:21