Skip to content

Commit ae82875

Browse files
Fix parameter updates and tests after rebase
1 parent 69ad1b6 commit ae82875

File tree

3 files changed

+36
-31
lines changed

3 files changed

+36
-31
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 8 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -126,26 +126,18 @@ controller_interface::return_type JointTrajectoryController::update(
126126
if (param_listener_->is_old(params_))
127127
{
128128
params_ = param_listener_->get_params();
129-
// use_closed_loop_pid_adapter_ is updated in on_configure only
130-
if (use_closed_loop_pid_adapter_)
129+
default_tolerances_ = get_segment_tolerances(params_);
130+
// update gains of controller
131+
if (traj_contr_)
131132
{
132-
update_pids();
133-
default_tolerances_ = get_segment_tolerances(params_);
133+
if (traj_contr_->updateGainsRT() == false)
134+
{
135+
RCLCPP_ERROR(get_node()->get_logger(), "Could not update gains of controller");
136+
return controller_interface::return_type::ERROR;
137+
}
134138
}
135139
}
136140

137-
// update gains of controller
138-
// TODO(christophfroehlich) activate this
139-
// once https://github.com/ros-controls/ros2_controllers/pull/761 is merged
140-
// if (traj_contr_)
141-
// {
142-
// if(traj_contr_->updateGainsRT() == false)
143-
// {
144-
// RCLCPP_ERROR(get_node()->get_logger(), "Could not update gains of controller");
145-
// return controller_interface::return_type::ERROR;
146-
// }
147-
// }
148-
149141
auto compute_error_for_joint = [&](
150142
JointTrajectoryPoint & error, size_t index,
151143
const JointTrajectoryPoint & current,
@@ -1071,7 +1063,6 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
10711063
{
10721064
cmd_timeout_ = 0.0;
10731065
}
1074-
10751066
return CallbackReturn::SUCCESS;
10761067
}
10771068

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 18 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -420,30 +420,38 @@ TEST_P(TrajectoryControllerTestParameterized, update_dynamic_parameters)
420420
{
421421
rclcpp::executors::MultiThreadedExecutor executor;
422422

423+
// with kp = 0.0
423424
SetUpAndActivateTrajectoryController(executor);
424425

425426
updateController();
426-
auto pids = traj_controller_->get_pids();
427+
auto pids = traj_controller_->get_traj_contr();
427428

428-
if (traj_controller_->use_closed_loop_pid_adapter())
429+
if (traj_controller_->use_external_control_law())
429430
{
430-
EXPECT_EQ(pids.size(), 3);
431-
auto gain_0 = pids.at(0)->getGains();
432-
EXPECT_EQ(gain_0.p_gain_, 0.0);
431+
std::vector<double> tmp_command{0.0, 0.0, 0.0};
432+
trajectory_msgs::msg::JointTrajectoryPoint error;
433+
error.positions = {1.0, 0.0, 0.0};
434+
error.velocities = {0.0, 0.0, 0.0};
435+
trajectory_msgs::msg::JointTrajectoryPoint current;
436+
trajectory_msgs::msg::JointTrajectoryPoint desired;
437+
desired.velocities = {0.0, 0.0, 0.0};
438+
rclcpp::Duration duration_since_start(std::chrono::milliseconds(250));
439+
rclcpp::Duration period(std::chrono::milliseconds(100));
440+
441+
pids->computeCommands(tmp_command, current, error, desired, duration_since_start, period);
442+
EXPECT_EQ(tmp_command.at(0), 0.0);
433443

434444
double kp = 1.0;
435445
SetPidParameters(kp);
436446
updateController();
437447

438-
pids = traj_controller_->get_pids();
439-
EXPECT_EQ(pids.size(), 3);
440-
gain_0 = pids.at(0)->getGains();
441-
EXPECT_EQ(gain_0.p_gain_, kp);
448+
pids->computeCommands(tmp_command, current, error, desired, duration_since_start, period);
449+
EXPECT_EQ(tmp_command.at(0), 1.0);
442450
}
443451
else
444452
{
445453
// nothing to check here, skip further test
446-
EXPECT_EQ(pids.size(), 0);
454+
EXPECT_EQ(pids, nullptr);
447455
}
448456

449457
executor.cancel();

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 10 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -116,7 +116,11 @@ class TestableJointTrajectoryController
116116

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

119-
std::vector<PidPtr> get_pids() const { return pids_; }
119+
std::shared_ptr<joint_trajectory_controller_plugins::TrajectoryControllerBase> get_traj_contr()
120+
const
121+
{
122+
return traj_contr_;
123+
}
120124

121125
bool has_active_traj() const { return has_active_trajectory(); }
122126

@@ -193,7 +197,8 @@ class TrajectoryControllerTest : public ::testing::Test
193197
for (size_t i = 0; i < joint_names_.size(); ++i)
194198
{
195199
const std::string prefix = "gains." + joint_names_[i];
196-
const rclcpp::Parameter angle_wraparound(prefix + ".angle_wraparound", angle_wraparound_default);
200+
const rclcpp::Parameter angle_wraparound(
201+
prefix + ".angle_wraparound", angle_wraparound_default);
197202
node->set_parameters({angle_wraparound});
198203
}
199204
}
@@ -230,12 +235,13 @@ class TrajectoryControllerTest : public ::testing::Test
230235
{
231236
SetUpTrajectoryController(executor);
232237

238+
SetJointParameters(angle_wraparound);
239+
233240
// add this to simplify tests, can be overwritten by parameters
234241
rclcpp::Parameter nonzero_vel_parameter("allow_nonzero_velocity_at_trajectory_end", true);
235242
traj_controller_->get_node()->set_parameter(nonzero_vel_parameter);
236243

237-
SetJointParameters(normalize_error);
238-
244+
// set optional parameters
239245
for (const auto & param : parameters)
240246
{
241247
traj_controller_->get_node()->set_parameter(param);

0 commit comments

Comments
 (0)