Skip to content

Commit 8bc3e16

Browse files
Rename variable
1 parent f18adf7 commit 8bc3e16

File tree

4 files changed

+21
-21
lines changed

4 files changed

+21
-21
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
@@ -166,7 +166,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
166166
bool has_effort_command_interface_ = false;
167167

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

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -314,7 +314,7 @@ controller_interface::return_type JointTrajectoryController::update(
314314
}
315315
if (has_velocity_command_interface_)
316316
{
317-
if (use_closed_loop_control_law_)
317+
if (use_external_control_law_)
318318
{
319319
assign_interface_from_point(joint_command_interface_[1], tmp_command_);
320320
}
@@ -768,13 +768,13 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
768768
contains_interface_type(params_.command_interfaces, hardware_interface::HW_IF_EFFORT);
769769

770770
// if there is only velocity or if there is effort command interface
771-
// then use also closed-loop controller
772-
use_closed_loop_control_law_ =
771+
// then use external control law
772+
use_external_control_law_ =
773773
(has_velocity_command_interface_ && params_.command_interfaces.size() == 1 &&
774774
!params_.open_loop_control) ||
775775
has_effort_command_interface_;
776776

777-
if (use_closed_loop_control_law_)
777+
if (use_external_control_law_)
778778
{
779779
try
780780
{
@@ -802,7 +802,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
802802
{
803803
RCLCPP_FATAL(
804804
logger,
805-
"The trajectory controller plugin `%s` failed to initialize for some reason. Aborting.",
805+
"The trajectory controller plugin `%s` failed to configure for some reason. Aborting.",
806806
params_.controller_plugin.c_str());
807807
return CallbackReturn::FAILURE;
808808
}

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -533,8 +533,8 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_not_normalized)
533533
EXPECT_LT(0.0, state_msg->output.velocities[1]);
534534
EXPECT_LT(0.0, state_msg->output.velocities[2]);
535535

536-
// use_closed_loop_control_law_
537-
if (traj_controller_->use_closed_loop_control_law())
536+
// use_external_control_law_
537+
if (traj_controller_->use_external_control_law())
538538
{
539539
// we expect u = k_p * (s_d-s)
540540
EXPECT_NEAR(
@@ -773,8 +773,8 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_normalized)
773773

774774
if (traj_controller_->has_velocity_command_interface())
775775
{
776-
// use_closed_loop_control_law_
777-
if (traj_controller_->use_closed_loop_control_law())
776+
// use_external_control_law_
777+
if (traj_controller_->use_external_control_law())
778778
{
779779
// we expect u = k_p * (s_d-s) for positions[0] and positions[1]
780780
EXPECT_NEAR(
@@ -801,8 +801,8 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_normalized)
801801

802802
if (traj_controller_->has_effort_command_interface())
803803
{
804-
// use_closed_loop_control_law_
805-
if (traj_controller_->use_closed_loop_control_law())
804+
// use_external_control_law_
805+
if (traj_controller_->use_external_control_law())
806806
{
807807
// we expect u = k_p * (s_d-s) for positions[0] and positions[1]
808808
EXPECT_NEAR(
@@ -831,9 +831,9 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_normalized)
831831
}
832832

833833
/**
834-
* @brief check if use_closed_loop_pid is active
834+
* @brief check if use_external_control_law is set
835835
*/
836-
TEST_P(TrajectoryControllerTestParameterized, use_closed_loop_pid)
836+
TEST_P(TrajectoryControllerTestParameterized, set_external_control_law)
837837
{
838838
rclcpp::executors::MultiThreadedExecutor executor;
839839

@@ -847,7 +847,7 @@ TEST_P(TrajectoryControllerTestParameterized, use_closed_loop_pid)
847847
!traj_controller_->is_open_loop()) ||
848848
traj_controller_->has_effort_command_interface())
849849
{
850-
EXPECT_TRUE(traj_controller_->use_closed_loop_control_law());
850+
EXPECT_TRUE(traj_controller_->use_external_control_law());
851851
}
852852
}
853853

@@ -906,7 +906,7 @@ TEST_P(TrajectoryControllerTestParameterized, velocity_error)
906906
}
907907
// is the velocity error correct?
908908
if (
909-
traj_controller_->use_closed_loop_control_law() // always needed for PID controller
909+
traj_controller_->use_external_control_law() // always needed for PID controller
910910
|| (traj_controller_->has_velocity_state_interface() &&
911911
traj_controller_->has_velocity_command_interface()))
912912
{
@@ -972,8 +972,8 @@ TEST_P(TrajectoryControllerTestParameterized, test_jumbled_joint_order)
972972

973973
if (traj_controller_->has_velocity_command_interface())
974974
{
975-
// if use_closed_loop_control_law_==false: we expect desired velocities from direct sampling
976-
// if use_closed_loop_control_law_==true: we expect desired velocities, because we use PID with
975+
// if use_external_control_law_==false: we expect desired velocities from direct sampling
976+
// if use_external_control_law_==true: we expect desired velocities, because we use PID with
977977
// feedforward term only
978978
EXPECT_GT(0.0, joint_vel_[0]);
979979
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

@@ -238,7 +238,7 @@ class TrajectoryControllerTest : public ::testing::Test
238238

239239
// set pid parameters before activate. The PID plugin has to be loaded already, otherwise
240240
// parameters are not declared yet
241-
if (traj_controller_->use_closed_loop_control_law())
241+
if (traj_controller_->use_external_control_law())
242242
{
243243
SetPidParameters(k_p, ff);
244244
}
@@ -456,7 +456,7 @@ class TrajectoryControllerTest : public ::testing::Test
456456
// i.e., active but trivial trajectory (one point only)
457457
EXPECT_TRUE(traj_controller_->has_trivial_traj());
458458

459-
if (traj_controller_->use_closed_loop_control_law() == false)
459+
if (traj_controller_->use_external_control_law() == false)
460460
{
461461
if (traj_controller_->has_position_command_interface())
462462
{

0 commit comments

Comments
 (0)