Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions nav2_amcl/include/nav2_amcl/amcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,15 +100,15 @@ class AmclNode : public nav2::LifecycleNode
* @return rcl_interfaces::msg::SetParametersResult Result indicating whether the update is accepted.
*/
rcl_interfaces::msg::SetParametersResult validateParameterUpdatesCallback(
std::vector<rclcpp::Parameter> parameters);
const std::vector<rclcpp::Parameter> & parameters);

/**
* @brief Apply parameter updates after validation
* This callback is executed when parameters have been successfully updated.
* It updates the internal configuration of the node with the new parameter values.
* @param parameters List of parameters that have been updated.
*/
void updateParametersCallback(std::vector<rclcpp::Parameter> parameters);
void updateParametersCallback(const std::vector<rclcpp::Parameter> & parameters);

// Dynamic parameters handler
rclcpp::node_interfaces::PostSetParametersCallbackHandle::SharedPtr post_set_params_handler_;
Expand Down
6 changes: 3 additions & 3 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -993,11 +993,11 @@ AmclNode::initParameters()
}

rcl_interfaces::msg::SetParametersResult AmclNode::validateParameterUpdatesCallback(
std::vector<rclcpp::Parameter> parameters)
const std::vector<rclcpp::Parameter> & parameters)
{
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
for (auto parameter : parameters) {
for (const auto & parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find('.') != std::string::npos) {
Expand Down Expand Up @@ -1043,7 +1043,7 @@ rcl_interfaces::msg::SetParametersResult AmclNode::validateParameterUpdatesCallb

void
AmclNode::updateParametersCallback(
std::vector<rclcpp::Parameter> parameters)
const std::vector<rclcpp::Parameter> & parameters)
{
std::lock_guard<std::recursive_mutex> cfl(mutex_);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -168,15 +168,15 @@ class KinematicsHandler
* @return rcl_interfaces::msg::SetParametersResult Result indicating whether the update is accepted.
*/
rcl_interfaces::msg::SetParametersResult validateParameterUpdatesCallback(
std::vector<rclcpp::Parameter> parameters);
const std::vector<rclcpp::Parameter> & parameters);

/**
* @brief Apply parameter updates after validation
* This callback is executed when parameters have been successfully updated.
* It updates the internal configuration of the node with the new parameter values.
* @param parameters List of parameters that have been updated.
*/
void updateParametersCallback(std::vector<rclcpp::Parameter> parameters);
void updateParametersCallback(const std::vector<rclcpp::Parameter> & parameters);
void update_kinematics(KinematicParameters kinematics);
std::string plugin_name_;
};
Expand Down
8 changes: 4 additions & 4 deletions nav2_dwb_controller/dwb_plugins/src/kinematic_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -189,11 +189,11 @@ void KinematicsHandler::setSpeedLimit(
}

rcl_interfaces::msg::SetParametersResult KinematicsHandler::validateParameterUpdatesCallback(
std::vector<rclcpp::Parameter> parameters)
const std::vector<rclcpp::Parameter> & parameters)
{
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
for (auto parameter : parameters) {
for (const auto & parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find(plugin_name_ + ".") != 0) {
Expand Down Expand Up @@ -229,12 +229,12 @@ rcl_interfaces::msg::SetParametersResult KinematicsHandler::validateParameterUpd
}

void
KinematicsHandler::updateParametersCallback(std::vector<rclcpp::Parameter> parameters)
KinematicsHandler::updateParametersCallback(const std::vector<rclcpp::Parameter> & parameters)
{
rcl_interfaces::msg::SetParametersResult result;
KinematicParameters kinematics(*kinematics_.load());

for (auto parameter : parameters) {
for (const auto & parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find(plugin_name_ + ".") != 0) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,7 @@
#include <algorithm>
#include <mutex>

#include "nav2_util/odometry_utils.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "nav2_util/parameter_handler.hpp"
#include "nav2_ros_common/lifecycle_node.hpp"
#include "nav2_ros_common/node_utils.hpp"

Expand Down Expand Up @@ -59,39 +58,18 @@ struct Parameters
* @class nav2_graceful_controller::ParameterHandler
* @brief Handles parameters and dynamic parameters for GracefulMotionController
*/
class ParameterHandler
class ParameterHandler : public nav2_util::ParameterHandler<Parameters>
{
public:
/**
* @brief Constructor for nav2_graceful_controller::ParameterHandler
*/
ParameterHandler(
nav2::LifecycleNode::SharedPtr node,
const nav2::LifecycleNode::SharedPtr & node,
std::string & plugin_name,
rclcpp::Logger & logger, const double costmap_size_x);

/**
* @brief Destructor for nav2_graceful_controller::ParameterHandler
*/
~ParameterHandler();

std::mutex & getMutex() {return mutex_;}

Parameters * getParams() {return &params_;}

/**
* @brief Registers callbacks for dynamic parameter handling.
*/
void activate();

/**
* @brief Resets callbacks for dynamic parameter handling.
*/
void deactivate();

protected:
nav2::LifecycleNode::WeakPtr node_;

/**
* @brief Validate incoming parameter updates before applying them.
* This callback is triggered when one or more parameters are about to be updated.
Expand All @@ -101,23 +79,17 @@ class ParameterHandler
* @return rcl_interfaces::msg::SetParametersResult Result indicating whether the update is accepted.
*/
rcl_interfaces::msg::SetParametersResult validateParameterUpdatesCallback(
std::vector<rclcpp::Parameter> parameters);
const std::vector<rclcpp::Parameter> & parameters) override;

/**
* @brief Apply parameter updates after validation
* This callback is executed when parameters have been successfully updated.
* It updates the internal configuration of the node with the new parameter values.
* @param parameters List of parameters that have been updated.
*/
void updateParametersCallback(std::vector<rclcpp::Parameter> parameters);
void updateParametersCallback(const std::vector<rclcpp::Parameter> & parameters) override;

// Dynamic parameters handler
std::mutex mutex_;
rclcpp::node_interfaces::PostSetParametersCallbackHandle::SharedPtr post_set_params_handler_;
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr on_set_params_handler_;
Parameters params_;
std::string plugin_name_;
rclcpp::Logger logger_ {rclcpp::get_logger("GracefulMotionController")};
};

} // namespace nav2_graceful_controller
Expand Down
42 changes: 5 additions & 37 deletions nav2_graceful_controller/src/parameter_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,11 @@ using nav2::declare_parameter_if_not_declared;
using rcl_interfaces::msg::ParameterType;

ParameterHandler::ParameterHandler(
nav2::LifecycleNode::SharedPtr node, std::string & plugin_name,
const nav2::LifecycleNode::SharedPtr & node, std::string & plugin_name,
rclcpp::Logger & logger, const double costmap_size_x)
: nav2_util::ParameterHandler<Parameters>(node, logger)
{
node_ = node;
plugin_name_ = plugin_name;
logger_ = logger;

declare_parameter_if_not_declared(
node, plugin_name_ + ".transform_tolerance", rclcpp::ParameterValue(0.1));
declare_parameter_if_not_declared(
Expand Down Expand Up @@ -116,42 +114,12 @@ ParameterHandler::ParameterHandler(
}
}

void ParameterHandler::activate()
{
auto node = node_.lock();
post_set_params_handler_ = node->add_post_set_parameters_callback(
std::bind(
&ParameterHandler::updateParametersCallback,
this, std::placeholders::_1));
on_set_params_handler_ = node->add_on_set_parameters_callback(
std::bind(
&ParameterHandler::validateParameterUpdatesCallback,
this, std::placeholders::_1));
}

void ParameterHandler::deactivate()
{
auto node = node_.lock();
if (post_set_params_handler_ && node) {
node->remove_post_set_parameters_callback(post_set_params_handler_.get());
}
post_set_params_handler_.reset();
if (on_set_params_handler_ && node) {
node->remove_on_set_parameters_callback(on_set_params_handler_.get());
}
on_set_params_handler_.reset();
}

ParameterHandler::~ParameterHandler()
{
}

rcl_interfaces::msg::SetParametersResult ParameterHandler::validateParameterUpdatesCallback(
std::vector<rclcpp::Parameter> parameters)
const std::vector<rclcpp::Parameter> & parameters)
{
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
for (auto parameter : parameters) {
for (const auto & parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find(plugin_name_ + ".") != 0) {
Expand Down Expand Up @@ -187,7 +155,7 @@ rcl_interfaces::msg::SetParametersResult ParameterHandler::validateParameterUpda
}
void
ParameterHandler::updateParametersCallback(
std::vector<rclcpp::Parameter> parameters)
const std::vector<rclcpp::Parameter> & parameters)
{
std::lock_guard<std::mutex> lock_reinit(mutex_);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,7 @@

#include "rclcpp/rclcpp.hpp"
#include "nav2_ros_common/lifecycle_node.hpp"
#include "nav2_util/odometry_utils.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "nav2_util/parameter_handler.hpp"
#include "nav2_ros_common/node_utils.hpp"

namespace nav2_regulated_pure_pursuit_controller
Expand Down Expand Up @@ -69,47 +68,26 @@ struct Parameters
* @class nav2_regulated_pure_pursuit_controller::ParameterHandler
* @brief Handles parameters and dynamic parameters for RPP
*/
class ParameterHandler
class ParameterHandler : public nav2_util::ParameterHandler<Parameters>
{
public:
/**
* @brief Constructor for nav2_regulated_pure_pursuit_controller::ParameterHandler
*/
ParameterHandler(
nav2::LifecycleNode::SharedPtr node,
const nav2::LifecycleNode::SharedPtr & node,
std::string & plugin_name,
rclcpp::Logger & logger, const double costmap_size_x);

/**
* @brief Destrructor for nav2_regulated_pure_pursuit_controller::ParameterHandler
*/
~ParameterHandler();

std::mutex & getMutex() {return mutex_;}

Parameters * getParams() {return &params_;}

/**
* @brief Registers callbacks for dynamic parameter handling.
*/
void activate();

/**
* @brief Resets callbacks for dynamic parameter handling.
*/
void deactivate();

protected:
nav2::LifecycleNode::WeakPtr node_;

/**
* @brief Apply parameter updates after validation
* This callback is executed when parameters have been successfully updated.
* It updates the internal configuration of the node with the new parameter values.
* @param parameters List of parameters that have been updated.
*/
void
updateParametersCallback(std::vector<rclcpp::Parameter> parameters);
updateParametersCallback(const std::vector<rclcpp::Parameter> & parameters) override;

/**
* @brief Validate incoming parameter updates before applying them.
Expand All @@ -120,15 +98,9 @@ class ParameterHandler
* @return rcl_interfaces::msg::SetParametersResult Result indicating whether the update is accepted.
*/
rcl_interfaces::msg::SetParametersResult
validateParameterUpdatesCallback(std::vector<rclcpp::Parameter> parameters);
validateParameterUpdatesCallback(const std::vector<rclcpp::Parameter> & parameters) override;

// Dynamic parameters handler
std::mutex mutex_;
rclcpp::node_interfaces::PostSetParametersCallbackHandle::SharedPtr post_set_params_handler_;
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr on_set_params_handler_;
Parameters params_;
std::string plugin_name_;
rclcpp::Logger logger_ {rclcpp::get_logger("RegulatedPurePursuitController")};
};

} // namespace nav2_regulated_pure_pursuit_controller
Expand Down
41 changes: 5 additions & 36 deletions nav2_regulated_pure_pursuit_controller/src/parameter_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,12 @@ using nav2::declare_parameter_if_not_declared;
using rcl_interfaces::msg::ParameterType;

ParameterHandler::ParameterHandler(
nav2::LifecycleNode::SharedPtr node,
const nav2::LifecycleNode::SharedPtr & node,
std::string & plugin_name, rclcpp::Logger & logger,
const double costmap_size_x)
: nav2_util::ParameterHandler<Parameters>(node, logger)
{
node_ = node;
plugin_name_ = plugin_name;
logger_ = logger;

declare_parameter_if_not_declared(
node, plugin_name_ + ".desired_linear_vel", rclcpp::ParameterValue(0.5));
Expand Down Expand Up @@ -199,42 +198,12 @@ ParameterHandler::ParameterHandler(
}
}

void ParameterHandler::activate()
{
auto node = node_.lock();
post_set_params_handler_ = node->add_post_set_parameters_callback(
std::bind(
&ParameterHandler::updateParametersCallback,
this, std::placeholders::_1));
on_set_params_handler_ = node->add_on_set_parameters_callback(
std::bind(
&ParameterHandler::validateParameterUpdatesCallback,
this, std::placeholders::_1));
}

void ParameterHandler::deactivate()
{
auto node = node_.lock();
if (post_set_params_handler_ && node) {
node->remove_post_set_parameters_callback(post_set_params_handler_.get());
}
post_set_params_handler_.reset();
if (on_set_params_handler_ && node) {
node->remove_on_set_parameters_callback(on_set_params_handler_.get());
}
on_set_params_handler_.reset();
}

ParameterHandler::~ParameterHandler()
{
}

rcl_interfaces::msg::SetParametersResult ParameterHandler::validateParameterUpdatesCallback(
std::vector<rclcpp::Parameter> parameters)
const std::vector<rclcpp::Parameter> & parameters)
{
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
for (auto parameter : parameters) {
for (const auto & parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find(plugin_name_ + ".") != 0) {
Expand Down Expand Up @@ -270,7 +239,7 @@ rcl_interfaces::msg::SetParametersResult ParameterHandler::validateParameterUpda
}
void
ParameterHandler::updateParametersCallback(
std::vector<rclcpp::Parameter> parameters)
const std::vector<rclcpp::Parameter> & parameters)
{
std::lock_guard<std::mutex> lock_reinit(mutex_);

Expand Down
Loading
Loading