Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update API of PID class #1437

Merged
merged 5 commits into from
Feb 13, 2025
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -165,8 +165,7 @@ class HardwareInterfaceAdapter<hardware_interface::HW_IF_EFFORT>
// Time since the last call to update
const auto period = std::chrono::steady_clock::now() - last_update_time_;
// Update PIDs
double command =
pid_->computeCommand(error_position, error_velocity, static_cast<uint64_t>(period.count()));
double command = pid_->compute_command(error_position, error_velocity, period);
command = std::min<double>(
fabs(max_allowed_effort), std::max<double>(-fabs(max_allowed_effort), command));
joint_handle_->get().set_value(command);
Original file line number Diff line number Diff line change
@@ -290,9 +290,8 @@ controller_interface::return_type JointTrajectoryController::update(
for (auto i = 0ul; i < dof_; ++i)
{
tmp_command_[i] = (command_next_.velocities[i] * ff_velocity_scale_[i]) +
pids_[i]->computeCommand(
state_error_.positions[i], state_error_.velocities[i],
(uint64_t)period.nanoseconds());
pids_[i]->compute_command(
state_error_.positions[i], state_error_.velocities[i], period);
}
}

@@ -1582,7 +1581,7 @@ void JointTrajectoryController::update_pids()
if (pids_[i])
{
// update PIDs with gains from ROS parameters
pids_[i]->setGains(gains.p, gains.i, gains.d, gains.i_clamp, -gains.i_clamp);
pids_[i]->set_gains(gains.p, gains.i, gains.d, gains.i_clamp, -gains.i_clamp);
}
else
{
Original file line number Diff line number Diff line change
@@ -325,7 +325,7 @@ TEST_P(TrajectoryControllerTestParameterized, update_dynamic_parameters)
if (traj_controller_->use_closed_loop_pid_adapter())
{
EXPECT_EQ(pids.size(), 3);
auto gain_0 = pids.at(0)->getGains();
auto gain_0 = pids.at(0)->get_gains();
EXPECT_EQ(gain_0.p_gain_, 0.0);

double kp = 1.0;
@@ -334,7 +334,7 @@ TEST_P(TrajectoryControllerTestParameterized, update_dynamic_parameters)

pids = traj_controller_->get_pids();
EXPECT_EQ(pids.size(), 3);
gain_0 = pids.at(0)->getGains();
gain_0 = pids.at(0)->get_gains();
EXPECT_EQ(gain_0.p_gain_, kp);
}
else
8 changes: 4 additions & 4 deletions pid_controller/src/pid_controller.cpp
Original file line number Diff line number Diff line change
@@ -140,7 +140,7 @@ controller_interface::CallbackReturn PidController::configure_parameters()
// prefix should be interpreted as parameters prefix
pids_[i] =
std::make_shared<control_toolbox::PidROS>(get_node(), "gains." + params_.dof_names[i], true);
if (!pids_[i]->initPid())
if (!pids_[i]->initialize_from_ros_parameters())
{
return CallbackReturn::FAILURE;
}
@@ -539,19 +539,19 @@ controller_interface::return_type PidController::update_and_write_commands(
!std::isnan(measured_state_values_[dof_ + i]))
{
// use calculation with 'error' and 'error_dot'
tmp_command += pids_[i]->computeCommand(
tmp_command += pids_[i]->compute_command(
error, reference_interfaces_[dof_ + i] - measured_state_values_[dof_ + i], period);
}
else
{
// Fallback to calculation with 'error' only
tmp_command += pids_[i]->computeCommand(error, period);
tmp_command += pids_[i]->compute_command(error, period);
}
}
else
{
// use calculation with 'error' only
tmp_command += pids_[i]->computeCommand(error, period);
tmp_command += pids_[i]->compute_command(error, period);
}

// write calculated values