From f694d57313a3b9c57864931173ed86dcc5e85211 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Wed, 18 Dec 2024 12:15:06 +0000 Subject: [PATCH] Rename initialize methods --- include/control_toolbox/pid_ros.hpp | 11 ++++++----- src/pid_ros.cpp | 6 +++--- test/pid_parameters_tests.cpp | 2 +- 3 files changed, 10 insertions(+), 9 deletions(-) diff --git a/include/control_toolbox/pid_ros.hpp b/include/control_toolbox/pid_ros.hpp index b453601..c5c7802 100644 --- a/include/control_toolbox/pid_ros.hpp +++ b/include/control_toolbox/pid_ros.hpp @@ -123,14 +123,14 @@ class CONTROL_TOOLBOX_PUBLIC PidROS * \brief Initialize the PID controller based on already set parameters * \return True if all parameters are set (p, i, d, i_min and i_max), False otherwise */ - bool initialize(); + bool initialize_from_ros_parameters(); /*! * \brief Initialize the PID controller based on already set parameters * \return True if all parameters are set (p, i, d, i_min and i_max), False otherwise */ - [[deprecated("Use initialize() instead")]] bool initPid() { - return initialize(); + [[deprecated("Use initialize_from_ros_parameters() instead")]] bool initPid() { + return initialize_from_ros_parameters(); } /*! @@ -362,12 +362,13 @@ class CONTROL_TOOLBOX_PUBLIC PidROS bool get_boolean_param(const std::string & param_name, bool & value); /*! - * \param topic_prefix prefix to add to the pid parameters. + * \brief Set prefix for topic and parameter names + * \param[in] topic_prefix prefix to add to the pid parameters. * Per default is prefix interpreted as prefix for topics. * If not stated explicitly using "/" or "~", prefix is interpreted as global, i.e., * "/" will be added in front of topic prefix */ - void initialize(std::string topic_prefix); + void set_prefixes(std::string topic_prefix); rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr parameter_callback_; diff --git a/src/pid_ros.cpp b/src/pid_ros.cpp index 2d7b035..6628a8d 100644 --- a/src/pid_ros.cpp +++ b/src/pid_ros.cpp @@ -83,7 +83,7 @@ PidROS::PidROS( } else { - initialize(prefix); + set_prefixes(prefix); } state_pub_ = rclcpp::create_publisher( @@ -92,7 +92,7 @@ PidROS::PidROS( new realtime_tools::RealtimePublisher(state_pub_)); } -void PidROS::initialize(std::string topic_prefix) +void PidROS::set_prefixes(std::string topic_prefix) { param_prefix_ = topic_prefix; // If it starts with a "~", remove it @@ -164,7 +164,7 @@ bool PidROS::get_double_param(const std::string & param_name, double & value) } } -bool PidROS::initialize() +bool PidROS::initialize_from_ros_parameters() { double p, i, d, i_min, i_max; p = i = d = i_min = i_max = std::numeric_limits::quiet_NaN(); diff --git a/test/pid_parameters_tests.cpp b/test/pid_parameters_tests.cpp index 63affa7..2904586 100644 --- a/test/pid_parameters_tests.cpp +++ b/test/pid_parameters_tests.cpp @@ -344,7 +344,7 @@ TEST(PidParametersTest, GetParametersFromParams) TestablePidROS pid(node); - ASSERT_TRUE(pid.initialize()); + ASSERT_TRUE(pid.initialize_from_ros_parameters()); rclcpp::Parameter param_p; ASSERT_TRUE(node->get_parameter("p", param_p));