Skip to content

Commit

Permalink
Reduced frequencies again
Browse files Browse the repository at this point in the history
  • Loading branch information
mhl787156 committed Nov 30, 2021
1 parent de233c7 commit 44a87e9
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
2 changes: 1 addition & 1 deletion simple_offboard/launch/simple_offboard.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
<param name="reference_frames.$(var vehicle_namespace)/navigate_target" value="map"/>
<param name="reference_frames.$(var vehicle_namespace)/main_camera_optical" value="map"/>
<param name="setpoint_rate" value="15.0"/>
<param name="tf_broadcast_rate" value="20.0"/>
<param name="tf_broadcast_rate" value="10.0"/>
</node>

<node name="trajectory_handler" pkg="simple_offboard" exec="trajectory_handler" output="screen" respawn="true"/>
Expand Down
4 changes: 2 additions & 2 deletions simple_offboard/src/simple_offboard.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -294,8 +294,8 @@ SimpleOffboard::SimpleOffboard() :
this->get_parameters("reference_frames", this->reference_frames); // Params in format reference_frames.<frame_id>

// Get Timeout parameters
setpoint_rate = this->get_timeout_parameter("setpoint_rate", 30.0, true);
tf_broadcast_rate = this->get_timeout_parameter("tf_broadcast_rate", 60.0, true);
setpoint_rate = this->get_timeout_parameter("setpoint_rate", 15.0, true);
tf_broadcast_rate = this->get_timeout_parameter("tf_broadcast_rate", 10.0, true);
state_timeout = this->get_timeout_parameter("state_timeout", 3.0);
local_position_timeout = this->get_timeout_parameter("local_position_timeout", 2.0);
velocity_timeout = this->get_timeout_parameter("velocity_timeout", 2.0);
Expand Down

0 comments on commit 44a87e9

Please sign in to comment.