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

Expose action server result timeout as a parameter in bt navigator servers #3787

Merged
merged 11 commits into from
Sep 9, 2023
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,16 @@ BtActionServer<ActionT>::BtActionServer(
RCLCPP_INFO_STREAM(logger_, "Error_code parameters were set to:" << error_codes_str);
}
}

// Result timeout for the action server.
// In https://github.com/ros2/rcl/pull/1012 a change was introduced
// which makes action servers discard a goal handle if the result is not produced
// within 10 seconds. Since this may not be the case for all actions in
// Nav2, this timeout is exposed as a parameter and defaults to the previous
// expiration value of 15 minutes.
if (!node->has_parameter("action_server_result_timeout")) {
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
node->declare_parameter("action_server_result_timeout", 900.0);
}
}

template<class ActionT>
Expand Down Expand Up @@ -134,19 +144,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;
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
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
18 changes: 17 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,25 @@ class TimedBehavior : public nav2_core::Behavior
node->get_parameter("robot_base_frame", robot_base_frame_);
node->get_parameter("transform_tolerance", transform_tolerance_);

// Result timeout for the action server.
// In https://github.com/ros2/rcl/pull/1012 a change was introduced
// which makes action servers discard a goal handle if the result is not produced
// within 10 seconds. Since this may not be the case for all actions in
// Nav2, this timeout is exposed as a parameter and defaults to the previous
// expiration value of 15 minutes.
if (!node->has_parameter("action_server_result_timeout")) {
node->declare_parameter("action_server_result_timeout", 900.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
6 changes: 6 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,9 @@ bt_navigator:
odom_topic: /odom
bt_loop_duration: 10
default_server_timeout: 20
# timeout [s] for action servers to discard goal handles if not completed,
# 15 minutes previous default, see https://github.com/ros2/rcl/pull/1012
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 +280,9 @@ waypoint_follower:
ros__parameters:
loop_rate: 20
stop_on_failure: false
# timeout [s] for action servers to discard goal handles if not completed,
# 15 minutes previous default, see https://github.com/ros2/rcl/pull/1012
action_server_result_timeout: 900.0
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
Expand Down
6 changes: 6 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,9 @@ bt_navigator:
odom_topic: /odom
bt_loop_duration: 10
default_server_timeout: 20
# timeout [s] for action servers to discard goal handles if not completed,
# 15 minutes previous default, see https://github.com/ros2/rcl/pull/1012
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 +279,9 @@ waypoint_follower:
ros__parameters:
loop_rate: 20
stop_on_failure: false
# timeout [s] for action servers to discard goal handles if not completed,
# 15 minutes previous default, see https://github.com/ros2/rcl/pull/1012
action_server_result_timeout: 900.0
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
Expand Down
6 changes: 6 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,9 @@ bt_navigator:
odom_topic: /odom
bt_loop_duration: 10
default_server_timeout: 20
# timeout [s] for action servers to discard goal handles if not completed,
# 15 minutes previous default, see https://github.com/ros2/rcl/pull/1012
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 +327,9 @@ waypoint_follower:
ros__parameters:
loop_rate: 20
stop_on_failure: false
# timeout [s] for action servers to discard goal handles if not completed,
# 15 minutes previous default, see https://github.com/ros2/rcl/pull/1012
action_server_result_timeout: 900.0
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
Expand Down
6 changes: 6 additions & 0 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,9 @@ bt_navigator:
odom_topic: /odom
bt_loop_duration: 10
default_server_timeout: 20
# timeout [s] for action servers to discard goal handles if not completed,
# 15 minutes previous default, see https://github.com/ros2/rcl/pull/1012
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 +323,9 @@ waypoint_follower:
ros__parameters:
loop_rate: 20
stop_on_failure: false
# timeout [s] for action servers to discard goal handles if not completed,
# 15 minutes previous default, see https://github.com/ros2/rcl/pull/1012
action_server_result_timeout: 900.0
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
Expand Down
15 changes: 14 additions & 1 deletion nav2_controller/src/controller_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,14 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)

declare_parameter("controller_frequency", 20.0);

// Result timeout for the action server.
// In https://github.com/ros2/rcl/pull/1012 a change was introduced
// which makes action servers discard a goal handle if the result is not produced
// within 10 seconds. Since this may not be the case for all actions in
// Nav2, this timeout is exposed as a parameter and defaults to the previous
// expiration value of 15 minutes.
declare_parameter("action_server_result_timeout", 900.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 +235,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
17 changes: 15 additions & 2 deletions nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,14 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options)
declare_parameter("planner_plugins", default_ids_);
declare_parameter("expected_planner_frequency", 1.0);

// Result timeout for the action server.
// In https://github.com/ros2/rcl/pull/1012 a change was introduced
// which makes action servers discard a goal handle if the result is not produced
// within 10 seconds. Since this may not be the case for all actions in
// Nav2, this timeout is exposed as a parameter and defaults to the previous
// expiration value of 15 minutes.
declare_parameter("action_server_result_timeout", 900.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 +147,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
15 changes: 14 additions & 1 deletion nav2_smoother/src/nav2_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,14 @@ 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_);

// Result timeout for the action server.
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
// In https://github.com/ros2/rcl/pull/1012 a change was introduced
// which makes action servers discard a goal handle if the result is not produced
// within 10 seconds. Since this may not be the case for all actions in
// Nav2, this timeout is exposed as a parameter and defaults to the previous
// expiration value of 15 minutes.
declare_parameter("action_server_result_timeout", 900.0);
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
}

SmootherServer::~SmootherServer()
Expand Down Expand Up @@ -104,14 +112,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
19 changes: 18 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,15 @@ WaypointFollower::WaypointFollower(const rclcpp::NodeOptions & options)

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

// Result timeout for the action server.
// In https://github.com/ros2/rcl/pull/1012 a change was introduced
// which makes action servers discard a goal handle if the result is not produced
// within 10 seconds. Since this may not be the case for all actions in
// Nav2, this timeout is exposed as a parameter and defaults to the previous
// expiration value of 15 minutes.
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 +80,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