Skip to content

Removing action server timeout duration after fixes to ROS 2, Reverts 3787 #5183

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

Merged
merged 2 commits into from
May 20, 2025
Merged
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
Original file line number Diff line number Diff line change
Expand Up @@ -65,9 +65,6 @@ 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);
}
if (!node->has_parameter("always_reload_bt_xml")) {
node->declare_parameter("always_reload_bt_xml", false);
}
Expand Down Expand Up @@ -164,19 +161,13 @@ bool BtActionServer<ActionT>::on_configure()
node, "transform_tolerance", rclcpp::ParameterValue(0.1));
rclcpp::copy_all_parameter_values(node, client_node_);

// 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").as_double();
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),
nullptr, std::chrono::milliseconds(500), false, server_options);
nullptr, std::chrono::milliseconds(500), false);

// Get parameters for BT timeouts
int bt_loop_duration;
Expand Down
11 changes: 1 addition & 10 deletions nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,19 +135,10 @@ 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), nullptr, std::chrono::milliseconds(
500), false, server_options);
500), false);

local_collision_checker_ = local_collision_checker;
global_collision_checker_ = global_collision_checker;
Expand Down
2 changes: 0 additions & 2 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,6 @@ bt_navigator:
filter_duration: 0.3
default_server_timeout: 20
wait_for_service_timeout: 1000
action_server_result_timeout: 900.0
service_introspection_mode: "disabled"
navigators: ["navigate_to_pose", "navigate_through_poses"]
navigate_to_pose:
Expand Down Expand Up @@ -430,7 +429,6 @@ waypoint_follower:
loop_rate: 20
stop_on_failure: false
service_introspection_mode: "disabled"
action_server_result_timeout: 900.0
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
Expand Down
10 changes: 2 additions & 8 deletions nav2_controller/src/controller_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,6 @@ 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 @@ -224,11 +222,6 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
odom_sub_ = std::make_unique<nav_2d_utils::OdomSubscriber>(node);
vel_publisher_ = std::make_unique<nav2_util::TwistPublisher>(node, "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);

double costmap_update_timeout_dbl;
get_parameter("costmap_update_timeout", costmap_update_timeout_dbl);
costmap_update_timeout_ = rclcpp::Duration::from_seconds(costmap_update_timeout_dbl);
Expand All @@ -242,7 +235,8 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
std::bind(&ControllerServer::computeControl, this),
nullptr,
std::chrono::milliseconds(500),
true /*spin thread*/, server_options, use_realtime_priority_ /*soft realtime*/);
true /*spin thread*/, rcl_action_server_get_default_options(),
use_realtime_priority_ /*soft realtime*/);
} catch (const std::runtime_error & e) {
RCLCPP_ERROR(get_logger(), "Error creating action server! %s", e.what());
on_cleanup(state);
Expand Down
11 changes: 2 additions & 9 deletions nav2_docking/opennav_docking/src/docking_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,25 +85,18 @@ DockingServer::on_configure(const rclcpp_lifecycle::State & state)
get_parameter("odom_topic", odom_topic);
odom_sub_ = std::make_unique<nav_2d_utils::OdomSubscriber>(node, odom_topic);

double action_server_result_timeout;
nav2_util::declare_parameter_if_not_declared(
node, "action_server_result_timeout", rclcpp::ParameterValue(10.0));
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 dock / undock
docking_action_server_ = std::make_unique<DockingActionServer>(
node, "dock_robot",
std::bind(&DockingServer::dockRobot, this),
nullptr, std::chrono::milliseconds(500),
true, server_options);
true);

undocking_action_server_ = std::make_unique<UndockingActionServer>(
node, "undock_robot",
std::bind(&DockingServer::undockRobot, this),
nullptr, std::chrono::milliseconds(500),
true, server_options);
true);

// Create composed utilities
mutex_ = std::make_shared<std::mutex>();
Expand Down
10 changes: 2 additions & 8 deletions nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,6 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options)
// Declare this node's parameters
declare_parameter("planner_plugins", default_ids_);
declare_parameter("expected_planner_frequency", 1.0);
declare_parameter("action_server_result_timeout", 10.0);
declare_parameter("costmap_update_timeout", 1.0);

get_parameter("planner_plugins", planner_ids_);
Expand Down Expand Up @@ -148,11 +147,6 @@ 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);

double costmap_update_timeout_dbl;
get_parameter("costmap_update_timeout", costmap_update_timeout_dbl);
costmap_update_timeout_ = rclcpp::Duration::from_seconds(costmap_update_timeout_dbl);
Expand All @@ -164,15 +158,15 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & state)
std::bind(&PlannerServer::computePlan, this),
nullptr,
std::chrono::milliseconds(500),
true, server_options);
true);

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, server_options);
true);

return nav2_util::CallbackReturn::SUCCESS;
}
Expand Down
11 changes: 2 additions & 9 deletions nav2_smoother/src/nav2_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,8 +53,6 @@ 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 @@ -85,7 +83,7 @@ SmootherServer::on_configure(const rclcpp_lifecycle::State & state)
transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_);

std::string costmap_topic, footprint_topic, robot_base_frame;
double transform_tolerance;
double transform_tolerance = 0.1;
this->get_parameter("costmap_topic", costmap_topic);
this->get_parameter("footprint_topic", footprint_topic);
this->get_parameter("transform_tolerance", transform_tolerance);
Expand All @@ -107,19 +105,14 @@ SmootherServer::on_configure(const rclcpp_lifecycle::State & 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, server_options);
true);

return nav2_util::CallbackReturn::SUCCESS;
}
Expand Down
2 changes: 0 additions & 2 deletions nav2_system_tests/src/system/nav2_system_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,6 @@ bt_navigator:
bt_loop_duration: 10
filter_duration: 0.3
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 @@ -291,7 +290,6 @@ 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
10 changes: 2 additions & 8 deletions nav2_waypoint_follower/src/waypoint_follower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,6 @@ 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);

declare_parameter("global_frame_id", "map");

nav2_util::declare_parameter_if_not_declared(
Expand Down Expand Up @@ -78,10 +76,6 @@ 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").as_double();
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);

xyz_action_server_ = std::make_unique<ActionServer>(
get_node_base_interface(),
get_node_clock_interface(),
Expand All @@ -90,7 +84,7 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & state)
"follow_waypoints", std::bind(
&WaypointFollower::followWaypointsCallback,
this), nullptr, std::chrono::milliseconds(
500), false, server_options);
500), false);

from_ll_to_map_client_ = std::make_unique<
nav2_util::ServiceClient<robot_localization::srv::FromLL,
Expand All @@ -108,7 +102,7 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & state)
std::bind(
&WaypointFollower::followGPSWaypointsCallback,
this), nullptr, std::chrono::milliseconds(
500), false, server_options);
500), false);

try {
waypoint_task_executor_type_ = nav2_util::get_plugin_type_param(
Expand Down
Loading