Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Feature/add frequency tolerance parameter #1

Open
wants to merge 9 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion velodyne_driver/launch/nodelet_manager.launch
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
<arg name="pcap_time" default="false" />
<arg name="cut_angle" default="-0.01" />
<arg name="timestamp_first_packet" default="false" />
<arg name="diagnostic_frequency_tolerance" default="0.1" />

<!-- start nodelet manager -->
<node pkg="nodelet" type="nodelet" name="$(arg manager)" args="manager" output="screen"/>
Expand All @@ -37,6 +38,7 @@
<param name="pcap_time" value="$(arg pcap_time)"/>
<param name="cut_angle" value="$(arg cut_angle)"/>
<param name="timestamp_first_packet" value="$(arg timestamp_first_packet)"/>
</node>
<param name="diagnostic_frequency_tolerance" value="$(arg diagnostic_frequency_tolerance)"/>
</node>

</launch>
8 changes: 5 additions & 3 deletions velodyne_driver/src/driver/driver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ VelodyneDriver::VelodyneDriver(ros::NodeHandle node,
}
else if (cut_angle < (2*M_PI))
{
ROS_INFO_STREAM("Cut at specific angle feature activated. "
ROS_INFO_STREAM("Cut at specific angle feature activated. "
"Cutting velodyne points always at " << cut_angle << " rad.");
}
else
Expand All @@ -143,7 +143,7 @@ VelodyneDriver::VelodyneDriver(ros::NodeHandle node,
cut_angle = -0.01;
}

// Convert cut_angle from radian to one-hundredth degree,
// Convert cut_angle from radian to one-hundredth degree,
// which is used in velodyne packets
config_.cut_angle = int((cut_angle*360/(2*M_PI))*100);

Expand All @@ -165,11 +165,13 @@ VelodyneDriver::VelodyneDriver(ros::NodeHandle node,
diag_min_freq_ = diag_freq;
ROS_INFO("expected frequency: %.3f (Hz)", diag_freq);

double diagnostic_frequency_tolerance;
private_nh.param("diagnostic_frequency_tolerance", diagnostic_frequency_tolerance, 0.1);
using namespace diagnostic_updater;
diag_topic_.reset(new TopicDiagnostic("velodyne_packets", diagnostics_,
FrequencyStatusParam(&diag_min_freq_,
&diag_max_freq_,
0.1, 10),
cesar-lopez-mar marked this conversation as resolved.
Show resolved Hide resolved
diagnostic_frequency_tolerance, 10),
TimeStampStatusParam()));
diag_timer_ = private_nh.createTimer(ros::Duration(0.2), &VelodyneDriver::diagTimerCallback,this);

Expand Down