Skip to content

Commit e18bc66

Browse files
init_pid --> initialize
Co-authored-by: Sai Kishor Kothakota <[email protected]>
1 parent 589a555 commit e18bc66

File tree

6 files changed

+23
-23
lines changed

6 files changed

+23
-23
lines changed

include/control_toolbox/pid.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -89,7 +89,7 @@ namespace control_toolbox
8989
9090
\verbatim
9191
control_toolbox::Pid pid;
92-
pid.init_pid(6.0, 1.0, 2.0, 0.3, -0.3);
92+
pid.initialize(6.0, 1.0, 2.0, 0.3, -0.3);
9393
double position_desi_ = 0.5;
9494
...
9595
rclcpp::Time last_time = get_clock()->now();
@@ -197,7 +197,7 @@ class CONTROL_TOOLBOX_PUBLIC Pid
197197
*
198198
* \note New gains are not applied if i_min_ > i_max_
199199
*/
200-
void init_pid(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
200+
void initialize(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
201201

202202
/*!
203203
* \brief Zeros out Pid values and initialize Pid-gains and integral term limits
@@ -212,9 +212,9 @@ class CONTROL_TOOLBOX_PUBLIC Pid
212212
*
213213
* \note New gains are not applied if i_min_ > i_max_
214214
*/
215-
[[deprecated("Use init_pid() instead")]] void initPid(
215+
[[deprecated("Use initialize() instead")]] void initPid(
216216
double p, double i, double d, double i_max, double i_min, bool antiwindup = false) {
217-
init_pid(p, i, d, i_max, i_min, antiwindup);
217+
initialize(p, i, d, i_max, i_min, antiwindup);
218218
}
219219

220220
/*!

include/control_toolbox/pid_ros.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ class CONTROL_TOOLBOX_PUBLIC PidROS
101101
*
102102
* \note New gains are not applied if i_min_ > i_max_
103103
*/
104-
void init_pid(double p, double i, double d, double i_max, double i_min, bool antiwindup);
104+
void initialize(double p, double i, double d, double i_max, double i_min, bool antiwindup);
105105

106106
/*!
107107
* \brief Initialize the PID controller and set the parameters
@@ -114,9 +114,9 @@ class CONTROL_TOOLBOX_PUBLIC PidROS
114114
*
115115
* \note New gains are not applied if i_min_ > i_max_
116116
*/
117-
[[deprecated("Use init_pid() instead")]] void initPid(
117+
[[deprecated("Use initialize() instead")]] void initPid(
118118
double p, double i, double d, double i_max, double i_min, bool antiwindup) {
119-
init_pid(p, i, d, i_max, i_min, antiwindup);
119+
initialize(p, i, d, i_max, i_min, antiwindup);
120120
}
121121

122122
/*!
@@ -130,7 +130,7 @@ class CONTROL_TOOLBOX_PUBLIC PidROS
130130
* \return True if all parameters are set (p, i, d, i_min and i_max), False otherwise
131131
*/
132132
[[deprecated("Use init_pid() instead")]] bool initPid() {
133-
return init_pid();
133+
return initialize();
134134
}
135135

136136
/*!

src/pid.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ Pid::Pid(const Pid & source)
6868

6969
Pid::~Pid() {}
7070

71-
void Pid::init_pid(double p, double i, double d, double i_max, double i_min, bool antiwindup)
71+
void Pid::initialize(double p, double i, double d, double i_max, double i_min, bool antiwindup)
7272
{
7373
set_gains(p, i, d, i_max, i_min, antiwindup);
7474

src/pid_ros.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -164,7 +164,7 @@ bool PidROS::get_double_param(const std::string & param_name, double & value)
164164
}
165165
}
166166

167-
bool PidROS::init_pid()
167+
bool PidROS::initialize()
168168
{
169169
double p, i, d, i_min, i_max;
170170
p = i = d = i_min = i_max = std::numeric_limits<double>::quiet_NaN();
@@ -182,7 +182,7 @@ bool PidROS::init_pid()
182182
set_parameter_event_callback();
183183
}
184184

185-
pid_.init_pid(p, i, d, i_max, i_min, antiwindup);
185+
pid_.initialize(p, i, d, i_max, i_min, antiwindup);
186186

187187
return all_params_available;
188188
}
@@ -194,12 +194,12 @@ void PidROS::declare_param(const std::string & param_name, rclcpp::ParameterValu
194194
}
195195
}
196196

197-
void PidROS::init_pid(double p, double i, double d, double i_max, double i_min, bool antiwindup)
197+
void PidROS::initialize(double p, double i, double d, double i_max, double i_min, bool antiwindup)
198198
{
199199
if (i_min > i_max) {
200200
RCLCPP_ERROR(node_logging_->get_logger(), "received i_min > i_max, skip new gains");
201201
} else {
202-
pid_.init_pid(p, i, d, i_max, i_min, antiwindup);
202+
pid_.initialize(p, i, d, i_max, i_min, antiwindup);
203203

204204
declare_param(param_prefix_ + "p", rclcpp::ParameterValue(p));
205205
declare_param(param_prefix_ + "i", rclcpp::ParameterValue(i));

test/pid_parameters_tests.cpp

+8-8
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ void check_set_parameters(
5858
const double I_MIN = -10.0;
5959
const bool ANTIWINDUP = true;
6060

61-
ASSERT_NO_THROW(pid.init_pid(P, I, D, I_MAX, I_MIN, ANTIWINDUP));
61+
ASSERT_NO_THROW(pid.initialize(P, I, D, I_MAX, I_MIN, ANTIWINDUP));
6262

6363
rclcpp::Parameter param;
6464

@@ -115,7 +115,7 @@ TEST(PidParametersTest, InitPidTestBadParameter)
115115
const double I_MAX_BAD = -10.0;
116116
const double I_MIN_BAD = 10.0;
117117

118-
ASSERT_NO_THROW(pid.init_pid(P, I, D, I_MAX_BAD, I_MIN_BAD, false));
118+
ASSERT_NO_THROW(pid.initialize(P, I, D, I_MAX_BAD, I_MIN_BAD, false));
119119

120120
rclcpp::Parameter param;
121121

@@ -216,7 +216,7 @@ TEST(PidParametersTest, SetParametersTest)
216216
const double I_MIN = -10.0;
217217
const bool ANTIWINDUP = true;
218218

219-
pid.init_pid(P, I, D, I_MAX, I_MIN, ANTIWINDUP);
219+
pid.initialize(P, I, D, I_MAX, I_MIN, ANTIWINDUP);
220220

221221
rcl_interfaces::msg::SetParametersResult set_result;
222222

@@ -266,7 +266,7 @@ TEST(PidParametersTest, SetBadParametersTest)
266266
const double I_MIN_BAD = 20.0;
267267
const bool ANTIWINDUP = true;
268268

269-
pid.init_pid(P, I, D, I_MAX, I_MIN, ANTIWINDUP);
269+
pid.initialize(P, I, D, I_MAX, I_MIN, ANTIWINDUP);
270270

271271
rcl_interfaces::msg::SetParametersResult set_result;
272272

@@ -314,7 +314,7 @@ TEST(PidParametersTest, GetParametersTest)
314314
const double I_MIN = -10.0;
315315
const bool ANTIWINDUP = true;
316316

317-
pid.init_pid(0.0, 0.0, 0.0, 0.0, 0.0, false);
317+
pid.initialize(0.0, 0.0, 0.0, 0.0, 0.0, false);
318318
pid.set_gains(P, I, D, I_MAX, I_MIN, ANTIWINDUP);
319319

320320
rclcpp::Parameter param;
@@ -344,7 +344,7 @@ TEST(PidParametersTest, GetParametersFromParams)
344344

345345
TestablePidROS pid(node);
346346

347-
ASSERT_TRUE(pid.init_pid());
347+
ASSERT_TRUE(pid.initialize());
348348

349349
rclcpp::Parameter param_p;
350350
ASSERT_TRUE(node->get_parameter("p", param_p));
@@ -380,8 +380,8 @@ TEST(PidParametersTest, MultiplePidInstances)
380380
const double I_MAX = 10.0;
381381
const double I_MIN = -10.0;
382382

383-
ASSERT_NO_THROW(pid_1.init_pid(P, I, D, I_MAX, I_MIN, false));
384-
ASSERT_NO_THROW(pid_2.init_pid(P, I, D, I_MAX, I_MIN, true));
383+
ASSERT_NO_THROW(pid_1.initialize(P, I, D, I_MAX, I_MIN, false));
384+
ASSERT_NO_THROW(pid_2.initialize(P, I, D, I_MAX, I_MIN, true));
385385

386386
rclcpp::Parameter param_1, param_2;
387387
ASSERT_TRUE(node->get_parameter("PID_1.p", param_1));

test/pid_publisher_tests.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ TEST(PidPublisherTest, PublishTest)
3939

4040
control_toolbox::PidROS pid_ros = control_toolbox::PidROS(node);
4141

42-
pid_ros.init_pid(1.0, 1.0, 1.0, 5.0, -5.0, false);
42+
pid_ros.initialize(1.0, 1.0, 1.0, 5.0, -5.0, false);
4343

4444
bool callback_called = false;
4545
control_msgs::msg::PidState::SharedPtr last_state_msg;
@@ -77,7 +77,7 @@ TEST(PidPublisherTest, PublishTestLifecycle)
7777
pid_ros.get_pid_state_publisher());
7878
// state_pub_lifecycle_->on_activate();
7979

80-
pid_ros.init_pid(1.0, 1.0, 1.0, 5.0, -5.0, false);
80+
pid_ros.initialize(1.0, 1.0, 1.0, 5.0, -5.0, false);
8181

8282
bool callback_called = false;
8383
control_msgs::msg::PidState::SharedPtr last_state_msg;

0 commit comments

Comments
 (0)