Skip to content

Commit d979054

Browse files
authored
Use the new declare_or_get_parameter API for nav2_navfn_planner (#5681)
* Use the new declare_or_get_parameter API for nav2_navfn_planner Signed-off-by: Lee Hoin <[email protected]> * Removed using nav2::declare_parameter_if_not_declared from navfn_planner.cpp Signed-off-by: Lee Hoin <[email protected]> --------- Signed-off-by: Lee Hoin <[email protected]>
1 parent d536d33 commit d979054

File tree

1 file changed

+5
-10
lines changed

1 file changed

+5
-10
lines changed

nav2_navfn_planner/src/navfn_planner.cpp

Lines changed: 5 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,6 @@
4040

4141
using namespace std::chrono_literals;
4242
using namespace std::chrono; // NOLINT
43-
using nav2::declare_parameter_if_not_declared;
4443
using rcl_interfaces::msg::ParameterType;
4544
using std::placeholders::_1;
4645

@@ -81,15 +80,11 @@ NavfnPlanner::configure(
8180

8281
// Initialize parameters
8382
// Declare this plugin's parameters
84-
declare_parameter_if_not_declared(node, name + ".tolerance", rclcpp::ParameterValue(0.5));
85-
node->get_parameter(name + ".tolerance", tolerance_);
86-
declare_parameter_if_not_declared(node, name + ".use_astar", rclcpp::ParameterValue(false));
87-
node->get_parameter(name + ".use_astar", use_astar_);
88-
declare_parameter_if_not_declared(node, name + ".allow_unknown", rclcpp::ParameterValue(true));
89-
node->get_parameter(name + ".allow_unknown", allow_unknown_);
90-
declare_parameter_if_not_declared(
91-
node, name + ".use_final_approach_orientation", rclcpp::ParameterValue(false));
92-
node->get_parameter(name + ".use_final_approach_orientation", use_final_approach_orientation_);
83+
tolerance_ = node->declare_or_get_parameter(name + ".tolerance", 0.5);
84+
use_astar_ = node->declare_or_get_parameter(name + ".use_astar", false);
85+
allow_unknown_ = node->declare_or_get_parameter(name + ".allow_unknown", true);
86+
use_final_approach_orientation_ = node->declare_or_get_parameter(name +
87+
".use_final_approach_orientation", false);
9388

9489
// Create a planner based on the new costmap size
9590
planner_ = std::make_unique<NavFn>(

0 commit comments

Comments
 (0)