@@ -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