Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
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
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
00060 private_nh.param("model", config_.model, std::string("64E"));
00061 double packet_rate;
00062 std::string model_full_name;
00063 if ((config_.model == "64E_S2") ||
00064 (config_.model == "64E_S2.1"))
00065 {
00066 packet_rate = 3472.17;
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")
00075 {
00076 packet_rate = 5787.03;
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;
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);
00104
00105
00106
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
00133
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
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);
00146
00147
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
00165 if (dump_file != "")
00166 {
00167
00168 input_.reset(new velodyne_driver::InputPCAP(private_nh, udp_port,
00169 packet_rate, dump_file));
00170 }
00171 else
00172 {
00173
00174 input_.reset(new velodyne_driver::InputSocket(private_nh, udp_port));
00175 }
00176
00177
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
00192
00193 ros::Duration(1).sleep();
00194 return true;
00195 }
00196
00197
00198 velodyne_msgs::VelodyneScanPtr scan(new velodyne_msgs::VelodyneScan);
00199
00200 if( config_.cut_angle >= 0)
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;
00210 if (rc < 0) return false;
00211 }
00212 scan->packets.push_back(tmp_packet);
00213
00214
00215 std::size_t azimuth_data_pos = 100*0+2;
00216 int azimuth = *( (u_int16_t*) (&tmp_packet.data[azimuth_data_pos]));
00217
00218
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;
00229 }
00230 last_azimuth_ = azimuth;
00231 }
00232 }
00233 else
00234 {
00235
00236
00237 scan->packets.resize(config_.npackets);
00238 for (int i = 0; i < config_.npackets; ++i)
00239 {
00240 while (true)
00241 {
00242
00243 int rc = input_->getPacket(&scan->packets[i], config_.time_offset);
00244 if (rc == 0) break;
00245 if (rc < 0) return false;
00246 }
00247 }
00248 }
00249
00250
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
00257
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
00282 diagnostics_.update();
00283 }
00284
00285 }