@@ -37,8 +37,6 @@ WaypointFollower::WaypointFollower(const rclcpp::NodeOptions & options)
37
37
declare_parameter (" stop_on_failure" , true );
38
38
declare_parameter (" loop_rate" , 20 );
39
39
40
- declare_parameter (" action_server_result_timeout" , 900.0 );
41
-
42
40
declare_parameter (" global_frame_id" , " map" );
43
41
44
42
nav2_util::declare_parameter_if_not_declared (
@@ -78,10 +76,6 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & state)
78
76
get_node_waitables_interface (),
79
77
" navigate_to_pose" , callback_group_);
80
78
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
-
85
79
xyz_action_server_ = std::make_unique<ActionServer>(
86
80
get_node_base_interface (),
87
81
get_node_clock_interface (),
@@ -90,7 +84,7 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & state)
90
84
" follow_waypoints" , std::bind (
91
85
&WaypointFollower::followWaypointsCallback,
92
86
this ), nullptr , std::chrono::milliseconds (
93
- 500 ), false , server_options );
87
+ 500 ), false );
94
88
95
89
from_ll_to_map_client_ = std::make_unique<
96
90
nav2_util::ServiceClient<robot_localization::srv::FromLL,
@@ -108,7 +102,7 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & state)
108
102
std::bind (
109
103
&WaypointFollower::followGPSWaypointsCallback,
110
104
this ), nullptr , std::chrono::milliseconds (
111
- 500 ), false , server_options );
105
+ 500 ), false );
112
106
113
107
try {
114
108
waypoint_task_executor_type_ = nav2_util::get_plugin_type_param (
0 commit comments