From 76c2d02d74295510a2aaf3e183cdff5ca79410f8 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Tue, 4 Feb 2025 08:53:20 +0100 Subject: [PATCH] Update computeCommand to compute_command The former has been marked deprecated in control_toolbox. --- ur_controllers/src/scaled_joint_trajectory_controller.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ur_controllers/src/scaled_joint_trajectory_controller.cpp b/ur_controllers/src/scaled_joint_trajectory_controller.cpp index 4b99cee75..68d224738 100644 --- a/ur_controllers/src/scaled_joint_trajectory_controller.cpp +++ b/ur_controllers/src/scaled_joint_trajectory_controller.cpp @@ -237,8 +237,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const // Update PIDs for (auto i = 0ul; i < dof_; ++i) { tmp_command_[i] = (state_desired_.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); } }