Skip to content

Commit 48f81c3

Browse files
pepisgMarc-Morcos
authored andcommitted
Expose action server result timeout as a parameter in bt navigator servers (ros-navigation#3787)
* Expose action server default timeout in bt navigator servers * typo * duplicated comment * Expose result timeout in other actions * Proper timeout in bt node * Change default timeouts and remove comments * Remove comment in params file * uncrustify controller server
1 parent 6f44178 commit 48f81c3

File tree

2 files changed

+8
-0
lines changed

2 files changed

+8
-0
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -149,6 +149,12 @@ bool BtActionServer<ActionT>::on_configure()
149149
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
150150
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
151151

152+
// set the timeout in seconds for the action server to discard goal handles if not finished
153+
double action_server_result_timeout;
154+
node->get_parameter("action_server_result_timeout", action_server_result_timeout);
155+
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
156+
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
157+
152158
action_server_ = std::make_shared<ActionServer>(
153159
node->get_node_base_interface(),
154160
node->get_node_clock_interface(),

nav2_planner/src/planner_server.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,8 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options)
5454
declare_parameter("expected_planner_frequency", 1.0);
5555
declare_parameter("action_server_result_timeout", 10.0);
5656

57+
declare_parameter("action_server_result_timeout", 10.0);
58+
5759
get_parameter("planner_plugins", planner_ids_);
5860
if (planner_ids_ == default_ids_) {
5961
for (size_t i = 0; i < default_ids_.size(); ++i) {

0 commit comments

Comments
 (0)