43 #include <velodyne_msgs/VelodyneScan.h> 54 private_nh.
param(
"frame_id",
config_.frame_id, std::string(
"velodyne"));
60 private_nh.
param(
"model",
config_.model, std::string(
"64E"));
62 std::string model_full_name;
63 if ((
config_.model ==
"64E_S2") ||
66 packet_rate = 3472.17;
67 model_full_name = std::string(
"HDL-") +
config_.model;
69 else if (
config_.model ==
"64E")
72 model_full_name = std::string(
"HDL-") +
config_.model;
74 else if (
config_.model ==
"64E_S3")
76 packet_rate = 5787.03;
77 model_full_name = std::string(
"HDL-") +
config_.model;
79 else if (
config_.model ==
"32E")
82 model_full_name = std::string(
"HDL-") +
config_.model;
84 else if (
config_.model ==
"32C")
87 model_full_name = std::string(
"VLP-") +
config_.model;
89 else if (
config_.model ==
"VLP16")
92 model_full_name =
"VLP-16";
99 std::string deviceName(std::string(
"Velodyne ") + model_full_name);
103 double frequency = (
config_.rpm / 60.0);
107 config_.npackets = (int) ceil(packet_rate / frequency);
111 std::string dump_file;
112 private_nh.
param(
"pcap", dump_file, std::string(
""));
115 private_nh.
param(
"cut_angle", cut_angle, -0.01);
120 else if (cut_angle < (2*M_PI))
123 "Cutting velodyne points always at " << cut_angle <<
" rad.");
128 <<
"between 0.0 and 2*PI or negative values to deactivate this feature.");
134 config_.cut_angle = int((cut_angle*360/(2*M_PI))*100);
140 srv_ = boost::make_shared <dynamic_reconfigure::Server<velodyne_driver::
141 VelodyneNodeConfig> > (private_nh);
142 dynamic_reconfigure::Server<velodyne_driver::VelodyneNodeConfig>::
145 srv_->setCallback (f);
149 const double diag_freq = packet_rate/
config_.npackets;
152 ROS_INFO(
"expected frequency: %.3f (Hz)", diag_freq);
169 packet_rate, dump_file));
179 node.
advertise<velodyne_msgs::VelodyneScan>(
"velodyne_packets", 10);
198 velodyne_msgs::VelodyneScanPtr scan(
new velodyne_msgs::VelodyneScan);
202 scan->packets.reserve(
config_.npackets);
203 velodyne_msgs::VelodynePacket tmp_packet;
208 int rc =
input_->getPacket(&tmp_packet,
config_.time_offset);
210 if (rc < 0)
return false;
212 scan->packets.push_back(tmp_packet);
215 std::size_t azimuth_data_pos = 100*0+2;
216 int azimuth = *( (u_int16_t*) (&tmp_packet.data[azimuth_data_pos]));
237 scan->packets.resize(
config_.npackets);
238 for (
int i = 0; i <
config_.npackets; ++i)
243 int rc =
input_->getPacket(&scan->packets[i],
config_.time_offset);
245 if (rc < 0)
return false;
251 ROS_DEBUG(
"Publishing a full Velodyne scan.");
252 scan->header.stamp = scan->packets.back().stamp;
253 scan->header.frame_id =
config_.frame_id;
270 config_.time_offset = config.time_offset;
274 config_.enabled = config.enabled;
diagnostic_updater::Updater diagnostics_
static uint16_t DATA_PORT_NUMBER
void diagTimerCallback(const ros::TimerEvent &event)
void publish(const boost::shared_ptr< M > &message) const
std::string getPrefixParam(ros::NodeHandle &nh)
boost::shared_ptr< Input > input_
void setHardwareID(const std::string &hwid)
VelodyneDriver(ros::NodeHandle node, ros::NodeHandle private_nh)
std::string resolve(const std::string &prefix, const std::string &frame_name)
boost::shared_ptr< dynamic_reconfigure::Server< velodyne_driver::VelodyneNodeConfig > > srv_
bool param(const std::string ¶m_name, T ¶m_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)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
struct velodyne_driver::VelodyneDriver::@0 config_
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > diag_topic_
#define ROS_ERROR_STREAM(args)