Skip to content

Commit 441b556

Browse files
Rename variable
1 parent b2adbcd commit 441b556

File tree

4 files changed

+24
-25
lines changed

4 files changed

+24
-25
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -164,7 +164,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
164164
bool has_effort_command_interface_ = false;
165165

166166
/// If true, a velocity feedforward term plus corrective PID term is used
167-
bool use_closed_loop_control_law_ = false;
167+
bool use_external_control_law_ = false;
168168
// class loader for actual trajectory controller
169169
std::shared_ptr<
170170
pluginlib::ClassLoader<joint_trajectory_controller_plugins::TrajectoryControllerBase>>

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ controller_interface::return_type JointTrajectoryController::update(
130130

131131
// update gains of controller
132132
// variable use_closed_loop_control_law_ is updated in on_configure only
133-
if (use_closed_loop_control_law_)
133+
if (use_external_control_law_)
134134
{
135135
if (traj_contr_->updateGainsRT() == false)
136136
{
@@ -310,7 +310,7 @@ controller_interface::return_type JointTrajectoryController::update(
310310
}
311311
if (has_velocity_command_interface_)
312312
{
313-
if (use_closed_loop_control_law_)
313+
if (use_external_control_law_)
314314
{
315315
assign_interface_from_point(joint_command_interface_[1], tmp_command_);
316316
}
@@ -748,13 +748,13 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
748748
contains_interface_type(params_.command_interfaces, hardware_interface::HW_IF_EFFORT);
749749

750750
// if there is only velocity or if there is effort command interface
751-
// then use also closed-loop controller
752-
use_closed_loop_control_law_ =
751+
// then use external control law
752+
use_external_control_law_ =
753753
(has_velocity_command_interface_ && params_.command_interfaces.size() == 1 &&
754754
!params_.open_loop_control) ||
755755
has_effort_command_interface_;
756756

757-
if (use_closed_loop_control_law_)
757+
if (use_external_control_law_)
758758
{
759759
try
760760
{
@@ -782,7 +782,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
782782
{
783783
RCLCPP_FATAL(
784784
logger,
785-
"The trajectory controller plugin `%s` failed to initialize for some reason. Aborting.",
785+
"The trajectory controller plugin `%s` failed to configure for some reason. Aborting.",
786786
params_.controller_plugin.c_str());
787787
return CallbackReturn::FAILURE;
788788
}

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 14 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -367,7 +367,7 @@ TEST_P(TrajectoryControllerTestParameterized, update_dynamic_parameters)
367367
updateControllerAsync();
368368
auto pids = traj_controller_->get_pids();
369369

370-
if (traj_controller_->use_closed_loop_pid_adapter())
370+
if (traj_controller_->use_external_control_law())
371371
{
372372
EXPECT_EQ(pids.size(), 3);
373373
auto gain_0 = pids.at(0)->getGains();
@@ -525,8 +525,8 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_not_angle_wraparoun
525525

526526
if (traj_controller_->has_velocity_command_interface())
527527
{
528-
// use_closed_loop_pid_adapter_
529-
if (traj_controller_->use_closed_loop_pid_adapter())
528+
// use_external_control_law_
529+
if (traj_controller_->use_external_control_law())
530530
{
531531
// we expect u = k_p * (s_d-s) for positions
532532
EXPECT_NEAR(
@@ -551,8 +551,7 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_not_angle_wraparoun
551551

552552
if (traj_controller_->has_effort_command_interface())
553553
{
554-
// use_closed_loop_pid_adapter_
555-
if (traj_controller_->use_closed_loop_pid_adapter())
554+
if (traj_controller_->use_external_control_law())
556555
{
557556
// we expect u = k_p * (s_d-s) for positions
558557
EXPECT_NEAR(
@@ -638,8 +637,8 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_angle_wraparound)
638637

639638
if (traj_controller_->has_velocity_command_interface())
640639
{
641-
// use_closed_loop_pid_adapter_
642-
if (traj_controller_->use_closed_loop_pid_adapter())
640+
// use_external_control_law_
641+
if (traj_controller_->use_external_control_law())
643642
{
644643
// we expect u = k_p * (s_d-s) for positions[0] and positions[1]
645644
EXPECT_NEAR(
@@ -666,8 +665,8 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_angle_wraparound)
666665

667666
if (traj_controller_->has_effort_command_interface())
668667
{
669-
// use_closed_loop_pid_adapter_
670-
if (traj_controller_->use_closed_loop_pid_adapter())
668+
// use_external_control_law_
669+
if (traj_controller_->use_external_control_law())
671670
{
672671
// we expect u = k_p * (s_d-s) for positions[0] and positions[1]
673672
EXPECT_NEAR(
@@ -831,9 +830,9 @@ TEST_P(TrajectoryControllerTestParameterized, timeout)
831830
}
832831

833832
/**
834-
* @brief check if use_closed_loop_pid is active
833+
* @brief check if use_external_control_law is set
835834
*/
836-
TEST_P(TrajectoryControllerTestParameterized, use_closed_loop_pid)
835+
TEST_P(TrajectoryControllerTestParameterized, set_external_control_law)
837836
{
838837
rclcpp::executors::MultiThreadedExecutor executor;
839838

@@ -847,7 +846,7 @@ TEST_P(TrajectoryControllerTestParameterized, use_closed_loop_pid)
847846
!traj_controller_->is_open_loop()) ||
848847
traj_controller_->has_effort_command_interface())
849848
{
850-
EXPECT_TRUE(traj_controller_->use_closed_loop_control_law());
849+
EXPECT_TRUE(traj_controller_->use_external_control_law());
851850
}
852851
}
853852

@@ -904,7 +903,7 @@ TEST_P(TrajectoryControllerTestParameterized, velocity_error)
904903
}
905904
// is the velocity error correct?
906905
if (
907-
traj_controller_->use_closed_loop_control_law() // always needed for PID controller
906+
traj_controller_->use_external_control_law() // always needed for PID controller
908907
|| (traj_controller_->has_velocity_state_interface() &&
909908
traj_controller_->has_velocity_command_interface()))
910909
{
@@ -969,8 +968,8 @@ TEST_P(TrajectoryControllerTestParameterized, test_jumbled_joint_order)
969968

970969
if (traj_controller_->has_velocity_command_interface())
971970
{
972-
// if use_closed_loop_control_law_==false: we expect desired velocities from direct sampling
973-
// if use_closed_loop_control_law_==true: we expect desired velocities, because we use PID with
971+
// if use_external_control_law_==false: we expect desired velocities from direct sampling
972+
// if use_external_control_law_==true: we expect desired velocities, because we use PID with
974973
// feedforward term only
975974
EXPECT_GT(0.0, joint_vel_[0]);
976975
EXPECT_GT(0.0, joint_vel_[1]);

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -112,7 +112,7 @@ class TestableJointTrajectoryController
112112

113113
bool has_effort_command_interface() const { return has_effort_command_interface_; }
114114

115-
bool use_closed_loop_control_law() const { return use_closed_loop_control_law_; }
115+
bool use_external_control_law() const { return use_external_control_law_; }
116116

117117
bool is_open_loop() const { return params_.open_loop_control; }
118118

@@ -265,7 +265,7 @@ class TrajectoryControllerTest : public ::testing::Test
265265

266266
// set pid parameters before activate. The PID plugin has to be loaded already, otherwise
267267
// parameters are not declared yet
268-
if (traj_controller_->use_closed_loop_control_law())
268+
if (traj_controller_->use_external_control_law())
269269
{
270270
SetPidParameters(k_p, ff);
271271
}
@@ -535,7 +535,7 @@ class TrajectoryControllerTest : public ::testing::Test
535535
// i.e., active but trivial trajectory (one point only)
536536
EXPECT_TRUE(traj_controller_->has_trivial_traj());
537537

538-
if (traj_controller_->use_closed_loop_control_law() == false)
538+
if (traj_controller_->use_external_control_law() == false)
539539
{
540540
if (traj_controller_->has_position_command_interface())
541541
{

0 commit comments

Comments
 (0)