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 ==
"64E_S2") ||
68 packet_rate = 3472.17;
69 model_full_name = std::string(
"HDL-") +
config_.model;
71 else if (
config_.model ==
"64E")
74 model_full_name = std::string(
"HDL-") +
config_.model;
76 else if (
config_.model ==
"64E_S3")
78 packet_rate = 5787.03;
79 model_full_name = std::string(
"HDL-") +
config_.model;
81 else if (
config_.model ==
"32E")
84 model_full_name = std::string(
"HDL-") +
config_.model;
86 else if (
config_.model ==
"32C")
89 model_full_name = std::string(
"VLP-") +
config_.model;
91 else if (
config_.model ==
"VLP16")
94 model_full_name =
"VLP-16";
101 std::string deviceName(std::string(
"Velodyne ") + model_full_name);
105 double frequency = (
config_.rpm / 60.0);
109 config_.npackets = (int) ceil(packet_rate / frequency);
114 private_nh.
param(
"timestamp_first_packet",
config_.timestamp_first_packet,
false);
115 if (
config_.timestamp_first_packet)
116 ROS_INFO(
"Setting velodyne scan start time to timestamp of first packet");
118 std::string dump_file;
119 private_nh.
param(
"pcap", dump_file, std::string(
""));
122 private_nh.
param(
"cut_angle", cut_angle, -0.01);
127 else if (cut_angle < (2*M_PI))
130 "Cutting velodyne points always at " << cut_angle <<
" rad.");
135 <<
"between 0.0 and 2*PI or negative values to deactivate this feature.");
141 config_.cut_angle = int((cut_angle*360/(2*M_PI))*100);
147 srv_ = boost::make_shared <dynamic_reconfigure::Server<velodyne_driver::
148 VelodyneNodeConfig> > (private_nh);
149 dynamic_reconfigure::Server<velodyne_driver::VelodyneNodeConfig>::
152 srv_->setCallback (f);
156 const double diag_freq = packet_rate/
config_.npackets;
159 ROS_INFO(
"expected frequency: %.3f (Hz)", diag_freq);
176 packet_rate, dump_file));
186 node.
advertise<velodyne_msgs::VelodyneScan>(
"velodyne_packets", 10);
205 velodyne_msgs::VelodyneScanPtr scan(
new velodyne_msgs::VelodyneScan);
209 scan->packets.reserve(
config_.npackets);
210 velodyne_msgs::VelodynePacket tmp_packet;
215 int rc =
input_->getPacket(&tmp_packet,
config_.time_offset);
217 if (rc < 0)
return false;
219 scan->packets.push_back(tmp_packet);
222 std::size_t azimuth_data_pos = 100*0+2;
223 int azimuth = *( (u_int16_t*) (&tmp_packet.data[azimuth_data_pos]));
244 scan->packets.resize(
config_.npackets);
245 for (
int i = 0; i <
config_.npackets; ++i)
250 int rc =
input_->getPacket(&scan->packets[i],
config_.time_offset);
252 if (rc < 0)
return false;
258 ROS_DEBUG(
"Publishing a full Velodyne scan.");
259 if (
config_.timestamp_first_packet){
260 scan->header.stamp = scan->packets.front().stamp;
263 scan->header.stamp = scan->packets.back().stamp;
265 scan->header.frame_id =
config_.frame_id;
282 config_.time_offset = config.time_offset;
286 config_.enabled = config.enabled;
VelodyneDriver(ros::NodeHandle node, ros::NodeHandle private_nh, std::string const &node_name=ros::this_node::getName())
diagnostic_updater::Updater diagnostics_
static uint16_t DATA_PORT_NUMBER
void diagTimerCallback(const ros::TimerEvent &event)
std::string getPrefixParam(ros::NodeHandle &nh)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
boost::shared_ptr< Input > input_
void setHardwareID(const std::string &hwid)
std::string resolve(const std::string &prefix, const std::string &frame_name)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
bool getParam(const std::string &key, std::string &s) const
boost::shared_ptr< dynamic_reconfigure::Server< velodyne_driver::VelodyneNodeConfig > > srv_
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)
struct velodyne_driver::VelodyneDriver::@0 config_
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > diag_topic_
#define ROS_ERROR_STREAM(args)