Skip to content

Commit b3ab1a5

Browse files
Rename variable
1 parent 7a5e57a commit b3ab1a5

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
@@ -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: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -316,7 +316,7 @@ controller_interface::return_type JointTrajectoryController::update(
316316
}
317317
if (has_velocity_command_interface_)
318318
{
319-
if (use_closed_loop_control_law_)
319+
if (use_external_control_law_)
320320
{
321321
assign_interface_from_point(joint_command_interface_[1], tmp_command_);
322322
}
@@ -754,13 +754,13 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
754754
contains_interface_type(params_.command_interfaces, hardware_interface::HW_IF_EFFORT);
755755

756756
// if there is only velocity or if there is effort command interface
757-
// then use also closed-loop controller
758-
use_closed_loop_control_law_ =
757+
// then use external control law
758+
use_external_control_law_ =
759759
(has_velocity_command_interface_ && params_.command_interfaces.size() == 1 &&
760760
!params_.open_loop_control) ||
761761
has_effort_command_interface_;
762762

763-
if (use_closed_loop_control_law_)
763+
if (use_external_control_law_)
764764
{
765765
try
766766
{
@@ -788,7 +788,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
788788
{
789789
RCLCPP_FATAL(
790790
logger,
791-
"The trajectory controller plugin `%s` failed to initialize for some reason. Aborting.",
791+
"The trajectory controller plugin `%s` failed to configure for some reason. Aborting.",
792792
params_.controller_plugin.c_str());
793793
return CallbackReturn::FAILURE;
794794
}

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -567,8 +567,8 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_not_angle_wraparoun
567567
EXPECT_LT(0.0, state_msg->output.velocities[1]);
568568
EXPECT_LT(0.0, state_msg->output.velocities[2]);
569569

570-
// use_closed_loop_control_law_
571-
if (traj_controller_->use_closed_loop_control_law())
570+
// use_external_control_law_
571+
if (traj_controller_->use_external_control_law())
572572
{
573573
// we expect u = k_p * (s_d-s)
574574
EXPECT_NEAR(
@@ -806,8 +806,8 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_angle_wraparound)
806806

807807
if (traj_controller_->has_velocity_command_interface())
808808
{
809-
// use_closed_loop_control_law_
810-
if (traj_controller_->use_closed_loop_control_law())
809+
// use_external_control_law_
810+
if (traj_controller_->use_external_control_law())
811811
{
812812
// we expect u = k_p * (s_d-s) for positions[0] and positions[1]
813813
EXPECT_NEAR(
@@ -834,8 +834,8 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_angle_wraparound)
834834

835835
if (traj_controller_->has_effort_command_interface())
836836
{
837-
// use_closed_loop_control_law_
838-
if (traj_controller_->use_closed_loop_control_law())
837+
// use_external_control_law_
838+
if (traj_controller_->use_external_control_law())
839839
{
840840
// we expect u = k_p * (s_d-s) for positions[0] and positions[1]
841841
EXPECT_NEAR(
@@ -864,9 +864,9 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_angle_wraparound)
864864
}
865865

866866
/**
867-
* @brief check if use_closed_loop_pid is active
867+
* @brief check if use_external_control_law is set
868868
*/
869-
TEST_P(TrajectoryControllerTestParameterized, use_closed_loop_pid)
869+
TEST_P(TrajectoryControllerTestParameterized, set_external_control_law)
870870
{
871871
rclcpp::executors::MultiThreadedExecutor executor;
872872

@@ -880,7 +880,7 @@ TEST_P(TrajectoryControllerTestParameterized, use_closed_loop_pid)
880880
!traj_controller_->is_open_loop()) ||
881881
traj_controller_->has_effort_command_interface())
882882
{
883-
EXPECT_TRUE(traj_controller_->use_closed_loop_control_law());
883+
EXPECT_TRUE(traj_controller_->use_external_control_law());
884884
}
885885
}
886886

@@ -939,7 +939,7 @@ TEST_P(TrajectoryControllerTestParameterized, velocity_error)
939939
}
940940
// is the velocity error correct?
941941
if (
942-
traj_controller_->use_closed_loop_control_law() // always needed for PID controller
942+
traj_controller_->use_external_control_law() // always needed for PID controller
943943
|| (traj_controller_->has_velocity_state_interface() &&
944944
traj_controller_->has_velocity_command_interface()))
945945
{
@@ -1005,8 +1005,8 @@ TEST_P(TrajectoryControllerTestParameterized, test_jumbled_joint_order)
10051005

10061006
if (traj_controller_->has_velocity_command_interface())
10071007
{
1008-
// if use_closed_loop_control_law_==false: we expect desired velocities from direct sampling
1009-
// if use_closed_loop_control_law_==true: we expect desired velocities, because we use PID with
1008+
// if use_external_control_law_==false: we expect desired velocities from direct sampling
1009+
// if use_external_control_law_==true: we expect desired velocities, because we use PID with
10101010
// feedforward term only
10111011
EXPECT_GT(0.0, joint_vel_[0]);
10121012
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

@@ -245,7 +245,7 @@ class TrajectoryControllerTest : public ::testing::Test
245245

246246
// set pid parameters before activate. The PID plugin has to be loaded already, otherwise
247247
// parameters are not declared yet
248-
if (traj_controller_->use_closed_loop_control_law())
248+
if (traj_controller_->use_external_control_law())
249249
{
250250
SetPidParameters(k_p, ff);
251251
}
@@ -471,7 +471,7 @@ class TrajectoryControllerTest : public ::testing::Test
471471
// i.e., active but trivial trajectory (one point only)
472472
EXPECT_TRUE(traj_controller_->has_trivial_traj());
473473

474-
if (traj_controller_->use_closed_loop_control_law() == false)
474+
if (traj_controller_->use_external_control_law() == false)
475475
{
476476
if (traj_controller_->has_position_command_interface())
477477
{

0 commit comments

Comments
 (0)