Skip to content

Commit

Permalink
Merge pull request #27 from bricerebsamen/master
Browse files Browse the repository at this point in the history
fixed #16 (diagnostic rate for driver)
  • Loading branch information
jack-oquin committed Apr 24, 2014
2 parents da91bb9 + da56cd7 commit 53043fe
Showing 1 changed file with 4 additions and 3 deletions.
7 changes: 4 additions & 3 deletions velodyne_driver/src/driver/driver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -71,9 +71,10 @@ VelodyneDriver::VelodyneDriver(ros::NodeHandle node,

// initialize diagnostics
diagnostics_.setHardwareID(deviceName);
diag_max_freq_ = frequency;
diag_min_freq_ = frequency;
ROS_INFO("expected frequency: %.3f (Hz)", frequency);
const double diag_freq = packet_rate/config_.npackets;
diag_max_freq_ = diag_freq;
diag_min_freq_ = diag_freq;
ROS_INFO("expected frequency: %.3f (Hz)", diag_freq);

using namespace diagnostic_updater;
diag_topic_.reset(new TopicDiagnostic("velodyne_packets", diagnostics_,
Expand Down

0 comments on commit 53043fe

Please sign in to comment.