Skip to content

Commit 8704fa7

Browse files
committed
Activate dynamic parameters callback in Avtivate stage
Signed-off-by: mini-1235 <[email protected]>
1 parent a2ac221 commit 8704fa7

File tree

7 files changed

+29
-3
lines changed

7 files changed

+29
-3
lines changed

nav2_amcl/src/amcl_node.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1055,7 +1055,9 @@ AmclNode::updateParametersCallback(
10551055
for (const auto & parameter : parameters) {
10561056
const auto & param_type = parameter.get_type();
10571057
const auto & param_name = parameter.get_name();
1058-
1058+
if (param_name.find('.') != std::string::npos) {
1059+
continue;
1060+
}
10591061
if (param_type == ParameterType::PARAMETER_DOUBLE) {
10601062
if (param_name == "alpha1") {
10611063
alpha1_ = parameter.as_double();

nav2_graceful_controller/include/nav2_graceful_controller/parameter_handler.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -79,6 +79,11 @@ class ParameterHandler
7979

8080
Parameters * getParams() {return &params_;}
8181

82+
/**
83+
* @brief Registers callbacks for dynamic parameter handling.
84+
*/
85+
void activateDynamicParametersCallback();
86+
8287
protected:
8388
nav2::LifecycleNode::WeakPtr node_;
8489

nav2_graceful_controller/src/graceful_controller.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -97,6 +97,7 @@ void GracefulController::activate()
9797
local_plan_pub_->on_activate();
9898
motion_target_pub_->on_activate();
9999
slowdown_pub_->on_activate();
100+
param_handler_->activateDynamicParametersCallback();
100101
}
101102

102103
void GracefulController::deactivate()

nav2_graceful_controller/src/parameter_handler.cpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -114,7 +114,11 @@ ParameterHandler::ParameterHandler(
114114
"setting allow backward to false.");
115115
params_.allow_backward = false;
116116
}
117+
}
117118

119+
void ParameterHandler::activateDynamicParametersCallback()
120+
{
121+
auto node = node_.lock();
118122
post_set_params_handler_ = node->add_post_set_parameters_callback(
119123
std::bind(
120124
&ParameterHandler::updateParametersCallback,
@@ -186,7 +190,9 @@ ParameterHandler::updateParametersCallback(
186190
for (const auto & parameter : parameters) {
187191
const auto & param_type = parameter.get_type();
188192
const auto & param_name = parameter.get_name();
189-
193+
if (param_name.find(plugin_name_ + ".") != 0) {
194+
continue;
195+
}
190196
if (param_type == ParameterType::PARAMETER_DOUBLE) {
191197
if (param_name == plugin_name_ + ".transform_tolerance") {
192198
params_.transform_tolerance = parameter.as_double();

nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/parameter_handler.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -89,6 +89,11 @@ class ParameterHandler
8989

9090
Parameters * getParams() {return &params_;}
9191

92+
/**
93+
* @brief Registers callbacks for dynamic parameter handling.
94+
*/
95+
void activateDynamicParametersCallback();
96+
9297
protected:
9398
nav2::LifecycleNode::WeakPtr node_;
9499

nav2_regulated_pure_pursuit_controller/src/parameter_handler.cpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -197,7 +197,11 @@ ParameterHandler::ParameterHandler(
197197
"it should be >0. Disabling cost regulated linear velocity scaling.");
198198
params_.use_cost_regulated_linear_velocity_scaling = false;
199199
}
200+
}
200201

202+
void ParameterHandler::activateDynamicParametersCallback()
203+
{
204+
auto node = node_.lock();
201205
post_set_params_handler_ = node->add_post_set_parameters_callback(
202206
std::bind(
203207
&ParameterHandler::updateParametersCallback,
@@ -268,7 +272,9 @@ ParameterHandler::updateParametersCallback(
268272
for (const auto & parameter : parameters) {
269273
const auto & param_type = parameter.get_type();
270274
const auto & param_name = parameter.get_name();
271-
275+
if (param_name.find(plugin_name_ + ".") != 0) {
276+
continue;
277+
}
272278
if (param_type == ParameterType::PARAMETER_DOUBLE) {
273279
if (param_name == plugin_name_ + ".inflation_cost_scaling_factor") {
274280
params_.inflation_cost_scaling_factor = parameter.as_double();

nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -105,6 +105,7 @@ void RegulatedPurePursuitController::activate()
105105
carrot_pub_->on_activate();
106106
curvature_carrot_pub_->on_activate();
107107
is_rotating_to_heading_pub_->on_activate();
108+
param_handler_->activateDynamicParametersCallback();
108109
}
109110

110111
void RegulatedPurePursuitController::deactivate()

0 commit comments

Comments
 (0)