Skip to content

Commit 51da629

Browse files
authored
Ignore deprecation warning for set_gains for now (UniversalRobots#1392)
The upstream API isn't finalized, yet. For now, let's ignore the deprecation warning in order to not fail our builds.
1 parent b0d3413 commit 51da629

File tree

1 file changed

+3
-0
lines changed

1 file changed

+3
-0
lines changed

ur_controllers/src/scaled_joint_trajectory_controller.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -354,7 +354,10 @@ void ScaledJointTrajectoryController::update_pids()
354354
const auto& gains = params_.gains.joints_map.at(params_.joints.at(map_cmd_to_joints_[i]));
355355
if (pids_[i]) {
356356
// update PIDs with gains from ROS parameters
357+
#pragma GCC diagnostic push
358+
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
357359
pids_[i]->set_gains(gains.p, gains.i, gains.d, gains.i_clamp, -gains.i_clamp);
360+
#pragma GCC diagnostic pop
358361
} else {
359362
// Init PIDs with gains from ROS parameters
360363
pids_[i] = std::make_shared<control_toolbox::Pid>(gains.p, gains.i, gains.d, gains.i_clamp, -gains.i_clamp);

0 commit comments

Comments
 (0)