43 #include <velodyne_msgs/VelodyneScan.h>
52 std::string
const & node_name)
53 : diagnostics_(node, private_nh, node_name)
56 private_nh.
param(
"frame_id",
config_.frame_id, std::string(
"velodyne"));
62 private_nh.
param(
"model",
config_.model, std::string(
"64E"));
64 std::string model_full_name;
65 if ((
config_.model ==
"VLS128") )
70 model_full_name =
config_.model;
72 else if ((
config_.model ==
"64E_S2") ||
75 packet_rate = 3472.17;
76 model_full_name = std::string(
"HDL-") +
config_.model;
78 else if (
config_.model ==
"64E")
81 model_full_name = std::string(
"HDL-") +
config_.model;
83 else if (
config_.model ==
"64E_S3")
85 packet_rate = 5787.03;
86 model_full_name = std::string(
"HDL-") +
config_.model;
88 else if (
config_.model ==
"32E")
91 model_full_name = std::string(
"HDL-") +
config_.model;
93 else if (
config_.model ==
"32C")
96 model_full_name = std::string(
"VLP-") +
config_.model;
98 else if (
config_.model ==
"VLP16")
101 model_full_name =
"VLP-16";
106 packet_rate = 2600.0;
108 std::string deviceName(std::string(
"Velodyne ") + model_full_name);
112 double frequency = (
config_.rpm / 60.0);
116 config_.npackets = (int) ceil(packet_rate / frequency);
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");
125 std::string dump_file;
126 private_nh.
param(
"pcap", dump_file, std::string(
""));
137 "Cutting velodyne points always at " <<
cut_angle <<
" rad.");
142 <<
"between 0.0 and 2*PI or negative values to deactivate this feature.");
154 srv_ = boost::make_shared <dynamic_reconfigure::Server<velodyne_driver::
155 VelodyneNodeConfig> > (private_nh);
156 dynamic_reconfigure::Server<velodyne_driver::VelodyneNodeConfig>::
159 srv_->setCallback (
f);
163 const double diag_freq = packet_rate/
config_.npackets;
166 ROS_INFO(
"expected frequency: %.3f (Hz)", diag_freq);
168 double diagnostic_frequency_tolerance;
169 private_nh.
param(
"diagnostic_frequency_tolerance", diagnostic_frequency_tolerance, 0.1);
174 diagnostic_frequency_tolerance, 10),
185 packet_rate, dump_file));
195 node.
advertise<velodyne_msgs::VelodyneScan>(
"velodyne_packets", 10);
214 velodyne_msgs::VelodyneScanPtr scan(
new velodyne_msgs::VelodyneScan);
218 scan->packets.reserve(
config_.npackets);
219 velodyne_msgs::VelodynePacket tmp_packet;
224 int rc =
input_->getPacket(&tmp_packet,
config_.time_offset);
226 if (rc < 0)
return false;
227 if (rc == 0)
continue;
229 scan->packets.push_back(tmp_packet);
232 std::size_t azimuth_data_pos = 100*0+2;
233 int azimuth = *( (u_int16_t*) (&tmp_packet.data[azimuth_data_pos]));
254 scan->packets.resize(
config_.npackets);
255 for (
int i = 0; i <
config_.npackets; ++i)
260 int rc =
input_->getPacket(&scan->packets[i],
config_.time_offset);
262 if (rc < 0)
return false;
263 if (rc == 0)
continue;
269 ROS_DEBUG(
"Publishing a full Velodyne scan.");
270 if (
config_.timestamp_first_packet){
271 scan->header.stamp = scan->packets.front().stamp;
274 scan->header.stamp = scan->packets.back().stamp;
276 scan->header.frame_id =
config_.frame_id;
293 config_.time_offset = config.time_offset;
297 config_.enabled = config.enabled;