Skip to content

Commit c9438b4

Browse files
Removing action server timeout duration after fixes to ROS 2, Reverts 3787 (#5183)
* Removing action server timeout duration after fixes to ROS 2 Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * fix build warning Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> --------- Signed-off-by: Steve Macenski <stevenmacenski@gmail.com>
1 parent 42b8313 commit c9438b4

File tree

9 files changed

+12
-66
lines changed

9 files changed

+12
-66
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp

Lines changed: 1 addition & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -65,9 +65,6 @@ BtActionServer<ActionT>::BtActionServer(
6565
if (!node->has_parameter("default_server_timeout")) {
6666
node->declare_parameter("default_server_timeout", 20);
6767
}
68-
if (!node->has_parameter("action_server_result_timeout")) {
69-
node->declare_parameter("action_server_result_timeout", 900.0);
70-
}
7168
if (!node->has_parameter("always_reload_bt_xml")) {
7269
node->declare_parameter("always_reload_bt_xml", false);
7370
}
@@ -164,19 +161,13 @@ bool BtActionServer<ActionT>::on_configure()
164161
node, "transform_tolerance", rclcpp::ParameterValue(0.1));
165162
rclcpp::copy_all_parameter_values(node, client_node_);
166163

167-
// set the timeout in seconds for the action server to discard goal handles if not finished
168-
double action_server_result_timeout =
169-
node->get_parameter("action_server_result_timeout").as_double();
170-
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
171-
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
172-
173164
action_server_ = std::make_shared<ActionServer>(
174165
node->get_node_base_interface(),
175166
node->get_node_clock_interface(),
176167
node->get_node_logging_interface(),
177168
node->get_node_waitables_interface(),
178169
action_name_, std::bind(&BtActionServer<ActionT>::executeCallback, this),
179-
nullptr, std::chrono::milliseconds(500), false, server_options);
170+
nullptr, std::chrono::milliseconds(500), false);
180171

181172
// Get parameters for BT timeouts
182173
int bt_loop_duration;

nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp

Lines changed: 1 addition & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -135,19 +135,10 @@ class TimedBehavior : public nav2_core::Behavior
135135
node->get_parameter("robot_base_frame", robot_base_frame_);
136136
node->get_parameter("transform_tolerance", transform_tolerance_);
137137

138-
if (!node->has_parameter("action_server_result_timeout")) {
139-
node->declare_parameter("action_server_result_timeout", 10.0);
140-
}
141-
142-
double action_server_result_timeout;
143-
node->get_parameter("action_server_result_timeout", action_server_result_timeout);
144-
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
145-
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
146-
147138
action_server_ = std::make_shared<ActionServer>(
148139
node, behavior_name_,
149140
std::bind(&TimedBehavior::execute, this), nullptr, std::chrono::milliseconds(
150-
500), false, server_options);
141+
500), false);
151142

152143
local_collision_checker_ = local_collision_checker;
153144
global_collision_checker_ = global_collision_checker;

nav2_bringup/params/nav2_params.yaml

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,6 @@ bt_navigator:
4848
filter_duration: 0.3
4949
default_server_timeout: 20
5050
wait_for_service_timeout: 1000
51-
action_server_result_timeout: 900.0
5251
service_introspection_mode: "disabled"
5352
navigators: ["navigate_to_pose", "navigate_through_poses"]
5453
navigate_to_pose:
@@ -430,7 +429,6 @@ waypoint_follower:
430429
loop_rate: 20
431430
stop_on_failure: false
432431
service_introspection_mode: "disabled"
433-
action_server_result_timeout: 900.0
434432
waypoint_task_executor_plugin: "wait_at_waypoint"
435433
wait_at_waypoint:
436434
plugin: "nav2_waypoint_follower::WaitAtWaypoint"

nav2_controller/src/controller_server.cpp

Lines changed: 2 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -51,8 +51,6 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)
5151

5252
declare_parameter("controller_frequency", 20.0);
5353

54-
declare_parameter("action_server_result_timeout", 10.0);
55-
5654
declare_parameter("progress_checker_plugins", default_progress_checker_ids_);
5755
declare_parameter("goal_checker_plugins", default_goal_checker_ids_);
5856
declare_parameter("controller_plugins", default_ids_);
@@ -224,11 +222,6 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
224222
odom_sub_ = std::make_unique<nav_2d_utils::OdomSubscriber>(node);
225223
vel_publisher_ = std::make_unique<nav2_util::TwistPublisher>(node, "cmd_vel", 1);
226224

227-
double action_server_result_timeout;
228-
get_parameter("action_server_result_timeout", action_server_result_timeout);
229-
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
230-
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
231-
232225
double costmap_update_timeout_dbl;
233226
get_parameter("costmap_update_timeout", costmap_update_timeout_dbl);
234227
costmap_update_timeout_ = rclcpp::Duration::from_seconds(costmap_update_timeout_dbl);
@@ -242,7 +235,8 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
242235
std::bind(&ControllerServer::computeControl, this),
243236
nullptr,
244237
std::chrono::milliseconds(500),
245-
true /*spin thread*/, server_options, use_realtime_priority_ /*soft realtime*/);
238+
true /*spin thread*/, rcl_action_server_get_default_options(),
239+
use_realtime_priority_ /*soft realtime*/);
246240
} catch (const std::runtime_error & e) {
247241
RCLCPP_ERROR(get_logger(), "Error creating action server! %s", e.what());
248242
on_cleanup(state);

nav2_docking/opennav_docking/src/docking_server.cpp

Lines changed: 2 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -85,25 +85,18 @@ DockingServer::on_configure(const rclcpp_lifecycle::State & state)
8585
get_parameter("odom_topic", odom_topic);
8686
odom_sub_ = std::make_unique<nav_2d_utils::OdomSubscriber>(node, odom_topic);
8787

88-
double action_server_result_timeout;
89-
nav2_util::declare_parameter_if_not_declared(
90-
node, "action_server_result_timeout", rclcpp::ParameterValue(10.0));
91-
get_parameter("action_server_result_timeout", action_server_result_timeout);
92-
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
93-
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
94-
9588
// Create the action servers for dock / undock
9689
docking_action_server_ = std::make_unique<DockingActionServer>(
9790
node, "dock_robot",
9891
std::bind(&DockingServer::dockRobot, this),
9992
nullptr, std::chrono::milliseconds(500),
100-
true, server_options);
93+
true);
10194

10295
undocking_action_server_ = std::make_unique<UndockingActionServer>(
10396
node, "undock_robot",
10497
std::bind(&DockingServer::undockRobot, this),
10598
nullptr, std::chrono::milliseconds(500),
106-
true, server_options);
99+
true);
107100

108101
// Create composed utilities
109102
mutex_ = std::make_shared<std::mutex>();

nav2_planner/src/planner_server.cpp

Lines changed: 2 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,6 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options)
5252
// Declare this node's parameters
5353
declare_parameter("planner_plugins", default_ids_);
5454
declare_parameter("expected_planner_frequency", 1.0);
55-
declare_parameter("action_server_result_timeout", 10.0);
5655
declare_parameter("costmap_update_timeout", 1.0);
5756

5857
get_parameter("planner_plugins", planner_ids_);
@@ -148,11 +147,6 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & state)
148147
// Initialize pubs & subs
149148
plan_publisher_ = create_publisher<nav_msgs::msg::Path>("plan", 1);
150149

151-
double action_server_result_timeout;
152-
get_parameter("action_server_result_timeout", action_server_result_timeout);
153-
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
154-
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
155-
156150
double costmap_update_timeout_dbl;
157151
get_parameter("costmap_update_timeout", costmap_update_timeout_dbl);
158152
costmap_update_timeout_ = rclcpp::Duration::from_seconds(costmap_update_timeout_dbl);
@@ -164,15 +158,15 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & state)
164158
std::bind(&PlannerServer::computePlan, this),
165159
nullptr,
166160
std::chrono::milliseconds(500),
167-
true, server_options);
161+
true);
168162

169163
action_server_poses_ = std::make_unique<ActionServerThroughPoses>(
170164
shared_from_this(),
171165
"compute_path_through_poses",
172166
std::bind(&PlannerServer::computePlanThroughPoses, this),
173167
nullptr,
174168
std::chrono::milliseconds(500),
175-
true, server_options);
169+
true);
176170

177171
return nav2_util::CallbackReturn::SUCCESS;
178172
}

nav2_smoother/src/nav2_smoother.cpp

Lines changed: 2 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -53,8 +53,6 @@ SmootherServer::SmootherServer(const rclcpp::NodeOptions & options)
5353
rclcpp::ParameterValue(std::string("base_link")));
5454
declare_parameter("transform_tolerance", rclcpp::ParameterValue(0.1));
5555
declare_parameter("smoother_plugins", default_ids_);
56-
57-
declare_parameter("action_server_result_timeout", 10.0);
5856
}
5957

6058
SmootherServer::~SmootherServer()
@@ -85,7 +83,7 @@ SmootherServer::on_configure(const rclcpp_lifecycle::State & state)
8583
transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_);
8684

8785
std::string costmap_topic, footprint_topic, robot_base_frame;
88-
double transform_tolerance;
86+
double transform_tolerance = 0.1;
8987
this->get_parameter("costmap_topic", costmap_topic);
9088
this->get_parameter("footprint_topic", footprint_topic);
9189
this->get_parameter("transform_tolerance", transform_tolerance);
@@ -107,19 +105,14 @@ SmootherServer::on_configure(const rclcpp_lifecycle::State & state)
107105
// Initialize pubs & subs
108106
plan_publisher_ = create_publisher<nav_msgs::msg::Path>("plan_smoothed", 1);
109107

110-
double action_server_result_timeout;
111-
get_parameter("action_server_result_timeout", action_server_result_timeout);
112-
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
113-
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
114-
115108
// Create the action server that we implement with our smoothPath method
116109
action_server_ = std::make_unique<ActionServer>(
117110
shared_from_this(),
118111
"smooth_path",
119112
std::bind(&SmootherServer::smoothPlan, this),
120113
nullptr,
121114
std::chrono::milliseconds(500),
122-
true, server_options);
115+
true);
123116

124117
return nav2_util::CallbackReturn::SUCCESS;
125118
}

nav2_system_tests/src/system/nav2_system_params.yaml

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,6 @@ bt_navigator:
4646
bt_loop_duration: 10
4747
filter_duration: 0.3
4848
default_server_timeout: 20
49-
action_server_result_timeout: 900.0
5049
navigators: ["navigate_to_pose", "navigate_through_poses"]
5150
navigate_to_pose:
5251
plugin: "nav2_bt_navigator::NavigateToPoseNavigator"
@@ -291,7 +290,6 @@ waypoint_follower:
291290
ros__parameters:
292291
loop_rate: 20
293292
stop_on_failure: false
294-
action_server_result_timeout: 900.0
295293
waypoint_task_executor_plugin: "wait_at_waypoint"
296294
wait_at_waypoint:
297295
plugin: "nav2_waypoint_follower::WaitAtWaypoint"

nav2_waypoint_follower/src/waypoint_follower.cpp

Lines changed: 2 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -37,8 +37,6 @@ WaypointFollower::WaypointFollower(const rclcpp::NodeOptions & options)
3737
declare_parameter("stop_on_failure", true);
3838
declare_parameter("loop_rate", 20);
3939

40-
declare_parameter("action_server_result_timeout", 900.0);
41-
4240
declare_parameter("global_frame_id", "map");
4341

4442
nav2_util::declare_parameter_if_not_declared(
@@ -78,10 +76,6 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & state)
7876
get_node_waitables_interface(),
7977
"navigate_to_pose", callback_group_);
8078

81-
double action_server_result_timeout = get_parameter("action_server_result_timeout").as_double();
82-
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
83-
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
84-
8579
xyz_action_server_ = std::make_unique<ActionServer>(
8680
get_node_base_interface(),
8781
get_node_clock_interface(),
@@ -90,7 +84,7 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & state)
9084
"follow_waypoints", std::bind(
9185
&WaypointFollower::followWaypointsCallback,
9286
this), nullptr, std::chrono::milliseconds(
93-
500), false, server_options);
87+
500), false);
9488

9589
from_ll_to_map_client_ = std::make_unique<
9690
nav2_util::ServiceClient<robot_localization::srv::FromLL,
@@ -108,7 +102,7 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & state)
108102
std::bind(
109103
&WaypointFollower::followGPSWaypointsCallback,
110104
this), nullptr, std::chrono::milliseconds(
111-
500), false, server_options);
105+
500), false);
112106

113107
try {
114108
waypoint_task_executor_type_ = nav2_util::get_plugin_type_param(

0 commit comments

Comments
 (0)