Skip to content

Commit

Permalink
Expose action server result timeout as a parameter in bt navigator se…
Browse files Browse the repository at this point in the history
…rvers (#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
  • Loading branch information
pepisg authored Sep 9, 2023
1 parent bd47a94 commit 0976e63
Show file tree
Hide file tree
Showing 10 changed files with 73 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,9 @@ BtActionServer<ActionT>::BtActionServer(
if (!node->has_parameter("default_server_timeout")) {
node->declare_parameter("default_server_timeout", 20);
}
if (!node->has_parameter("action_server_result_timeout")) {
node->declare_parameter("action_server_result_timeout", 900.0);
}

std::vector<std::string> error_code_names = {
"follow_path_error_code",
Expand Down Expand Up @@ -134,19 +137,27 @@ bool BtActionServer<ActionT>::on_configure()
client_node_->declare_parameter(
"global_frame", node->get_parameter("global_frame").as_string());

// set the timeout in seconds for the action server to discard goal handles if not finished
double action_server_result_timeout;
node->get_parameter("action_server_result_timeout", action_server_result_timeout);
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);

action_server_ = std::make_shared<ActionServer>(
node->get_node_base_interface(),
node->get_node_clock_interface(),
node->get_node_logging_interface(),
node->get_node_waitables_interface(),
action_name_, std::bind(&BtActionServer<ActionT>::executeCallback, this));
action_name_, std::bind(&BtActionServer<ActionT>::executeCallback, this),
nullptr, std::chrono::milliseconds(500), false, server_options);

// Get parameters for BT timeouts
int timeout;
node->get_parameter("bt_loop_duration", timeout);
bt_loop_duration_ = std::chrono::milliseconds(timeout);
node->get_parameter("default_server_timeout", timeout);
default_server_timeout_ = std::chrono::milliseconds(timeout);
int bt_loop_duration;
node->get_parameter("bt_loop_duration", bt_loop_duration);
bt_loop_duration_ = std::chrono::milliseconds(bt_loop_duration);
int default_server_timeout;
node->get_parameter("default_server_timeout", default_server_timeout);
default_server_timeout_ = std::chrono::milliseconds(default_server_timeout);

// Get error code id names to grab off of the blackboard
error_code_names_ = node->get_parameter("error_code_names").as_string_array();
Expand Down
12 changes: 11 additions & 1 deletion nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,9 +133,19 @@ class TimedBehavior : public nav2_core::Behavior
node->get_parameter("robot_base_frame", robot_base_frame_);
node->get_parameter("transform_tolerance", transform_tolerance_);

if (!node->has_parameter("action_server_result_timeout")) {
node->declare_parameter("action_server_result_timeout", 10.0);
}

double action_server_result_timeout;
node->get_parameter("action_server_result_timeout", action_server_result_timeout);
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);

action_server_ = std::make_shared<ActionServer>(
node, behavior_name_,
std::bind(&TimedBehavior::execute, this));
std::bind(&TimedBehavior::execute, this), nullptr, std::chrono::milliseconds(
500), false, server_options);

local_collision_checker_ = local_collision_checker;
global_collision_checker_ = global_collision_checker;
Expand Down
2 changes: 2 additions & 0 deletions nav2_bringup/params/nav2_multirobot_params_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ bt_navigator:
odom_topic: /odom
bt_loop_duration: 10
default_server_timeout: 20
action_server_result_timeout: 900.0
navigators: ["navigate_to_pose", "navigate_through_poses"]
navigate_to_pose:
plugin: "nav2_bt_navigator/NavigateToPoseNavigator"
Expand Down Expand Up @@ -277,6 +278,7 @@ waypoint_follower:
ros__parameters:
loop_rate: 20
stop_on_failure: false
action_server_result_timeout: 900.0
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
Expand Down
2 changes: 2 additions & 0 deletions nav2_bringup/params/nav2_multirobot_params_2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ bt_navigator:
odom_topic: /odom
bt_loop_duration: 10
default_server_timeout: 20
action_server_result_timeout: 900.0
navigators: ["navigate_to_pose", "navigate_through_poses"]
navigate_to_pose:
plugin: "nav2_bt_navigator/NavigateToPoseNavigator"
Expand Down Expand Up @@ -276,6 +277,7 @@ waypoint_follower:
ros__parameters:
loop_rate: 20
stop_on_failure: false
action_server_result_timeout: 900.0
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
Expand Down
2 changes: 2 additions & 0 deletions nav2_bringup/params/nav2_multirobot_params_all.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ bt_navigator:
odom_topic: /odom
bt_loop_duration: 10
default_server_timeout: 20
action_server_result_timeout: 900.0
navigators: ["navigate_to_pose", "navigate_through_poses"]
navigate_to_pose:
plugin: "nav2_bt_navigator/NavigateToPoseNavigator"
Expand Down Expand Up @@ -324,6 +325,7 @@ waypoint_follower:
ros__parameters:
loop_rate: 20
stop_on_failure: false
action_server_result_timeout: 900.0
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
Expand Down
2 changes: 2 additions & 0 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ bt_navigator:
odom_topic: /odom
bt_loop_duration: 10
default_server_timeout: 20
action_server_result_timeout: 900.0
navigators: ["navigate_to_pose", "navigate_through_poses"]
navigate_to_pose:
plugin: "nav2_bt_navigator/NavigateToPoseNavigator"
Expand Down Expand Up @@ -320,6 +321,7 @@ waypoint_follower:
ros__parameters:
loop_rate: 20
stop_on_failure: false
action_server_result_timeout: 900.0
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
Expand Down
9 changes: 8 additions & 1 deletion nav2_controller/src/controller_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,8 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)

declare_parameter("controller_frequency", 20.0);

declare_parameter("action_server_result_timeout", 10.0);

declare_parameter("progress_checker_plugins", default_progress_checker_ids_);
declare_parameter("goal_checker_plugins", default_goal_checker_ids_);
declare_parameter("controller_plugins", default_ids_);
Expand Down Expand Up @@ -227,14 +229,19 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
odom_sub_ = std::make_unique<nav_2d_utils::OdomSubscriber>(node);
vel_publisher_ = create_publisher<geometry_msgs::msg::Twist>("cmd_vel", 1);

double action_server_result_timeout;
get_parameter("action_server_result_timeout", action_server_result_timeout);
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);

// Create the action server that we implement with our followPath method
action_server_ = std::make_unique<ActionServer>(
shared_from_this(),
"follow_path",
std::bind(&ControllerServer::computeControl, this),
nullptr,
std::chrono::milliseconds(500),
true);
true, server_options);

// Set subscribtion to the speed limiting topic
speed_limit_sub_ = create_subscription<nav2_msgs::msg::SpeedLimit>(
Expand Down
11 changes: 9 additions & 2 deletions nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,8 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options)
declare_parameter("planner_plugins", default_ids_);
declare_parameter("expected_planner_frequency", 1.0);

declare_parameter("action_server_result_timeout", 10.0);

get_parameter("planner_plugins", planner_ids_);
if (planner_ids_ == default_ids_) {
for (size_t i = 0; i < default_ids_.size(); ++i) {
Expand Down Expand Up @@ -139,22 +141,27 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
// Initialize pubs & subs
plan_publisher_ = create_publisher<nav_msgs::msg::Path>("plan", 1);

double action_server_result_timeout;
get_parameter("action_server_result_timeout", action_server_result_timeout);
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);

// Create the action servers for path planning to a pose and through poses
action_server_pose_ = std::make_unique<ActionServerToPose>(
shared_from_this(),
"compute_path_to_pose",
std::bind(&PlannerServer::computePlan, this),
nullptr,
std::chrono::milliseconds(500),
true);
true, server_options);

action_server_poses_ = std::make_unique<ActionServerThroughPoses>(
shared_from_this(),
"compute_path_through_poses",
std::bind(&PlannerServer::computePlanThroughPoses, this),
nullptr,
std::chrono::milliseconds(500),
true);
true, server_options);

return nav2_util::CallbackReturn::SUCCESS;
}
Expand Down
9 changes: 8 additions & 1 deletion nav2_smoother/src/nav2_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,8 @@ SmootherServer::SmootherServer(const rclcpp::NodeOptions & options)
rclcpp::ParameterValue(std::string("base_link")));
declare_parameter("transform_tolerance", rclcpp::ParameterValue(0.1));
declare_parameter("smoother_plugins", default_ids_);

declare_parameter("action_server_result_timeout", 10.0);
}

SmootherServer::~SmootherServer()
Expand Down Expand Up @@ -104,14 +106,19 @@ SmootherServer::on_configure(const rclcpp_lifecycle::State &)
// Initialize pubs & subs
plan_publisher_ = create_publisher<nav_msgs::msg::Path>("plan_smoothed", 1);

double action_server_result_timeout;
get_parameter("action_server_result_timeout", action_server_result_timeout);
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);

// Create the action server that we implement with our smoothPath method
action_server_ = std::make_unique<ActionServer>(
shared_from_this(),
"smooth_path",
std::bind(&SmootherServer::smoothPlan, this),
nullptr,
std::chrono::milliseconds(500),
true);
true, server_options);

return nav2_util::CallbackReturn::SUCCESS;
}
Expand Down
13 changes: 12 additions & 1 deletion nav2_waypoint_follower/src/waypoint_follower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,9 @@ WaypointFollower::WaypointFollower(const rclcpp::NodeOptions & options)

declare_parameter("stop_on_failure", true);
declare_parameter("loop_rate", 20);

declare_parameter("action_server_result_timeout", 900.0);

nav2_util::declare_parameter_if_not_declared(
this, std::string("waypoint_task_executor_plugin"),
rclcpp::ParameterValue(std::string("wait_at_waypoint")));
Expand Down Expand Up @@ -71,12 +74,20 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & /*state*/)
get_node_waitables_interface(),
"navigate_to_pose", callback_group_);

double action_server_result_timeout;
get_parameter("action_server_result_timeout", action_server_result_timeout);
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);

action_server_ = std::make_unique<ActionServer>(
get_node_base_interface(),
get_node_clock_interface(),
get_node_logging_interface(),
get_node_waitables_interface(),
"follow_waypoints", std::bind(&WaypointFollower::followWaypoints, this));
"follow_waypoints", std::bind(
&WaypointFollower::followWaypoints,
this), nullptr, std::chrono::milliseconds(
500), false, server_options);

try {
waypoint_task_executor_type_ = nav2_util::get_plugin_type_param(
Expand Down

0 comments on commit 0976e63

Please sign in to comment.