Skip to content

Commit 497bdfc

Browse files
committed
refactor: remove duplicate parameter initialization in waypoint_follower
1 parent dd7736a commit 497bdfc

File tree

1 file changed

+0
-8
lines changed

1 file changed

+0
-8
lines changed

‎nav2_waypoint_follower/src/waypoint_follower.cpp‎

Lines changed: 0 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -59,14 +59,6 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & state)
5959

6060
auto node = shared_from_this();
6161

62-
// Parameters already declared in constructor, just get them
63-
stop_on_failure_ = nav2::declare_or_get_parameter(node, "stop_on_failure", true);
64-
loop_rate_ = nav2::declare_or_get_parameter(node, "loop_rate", 20);
65-
waypoint_task_executor_id_ = nav2::declare_or_get_parameter(
66-
node, "waypoint_task_executor_plugin", std::string("wait_at_waypoint"));
67-
global_frame_id_ = nav2::declare_or_get_parameter(
68-
node, "global_frame_id", std::string("map"));
69-
7062
callback_group_ = create_callback_group(
7163
rclcpp::CallbackGroupType::MutuallyExclusive,
7264
false);

0 commit comments

Comments
 (0)