|
40 | 40 |
|
41 | 41 | using namespace std::chrono_literals; |
42 | 42 | using namespace std::chrono; // NOLINT |
43 | | -using nav2::declare_parameter_if_not_declared; |
44 | 43 | using rcl_interfaces::msg::ParameterType; |
45 | 44 | using std::placeholders::_1; |
46 | 45 |
|
@@ -81,15 +80,11 @@ NavfnPlanner::configure( |
81 | 80 |
|
82 | 81 | // Initialize parameters |
83 | 82 | // 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); |
93 | 88 |
|
94 | 89 | // Create a planner based on the new costmap size |
95 | 90 | planner_ = std::make_unique<NavFn>( |
|
0 commit comments