Skip to content

Commit b0e321f

Browse files
committed
Ignore RT-Tools deprecation warning about trylock
To update this the upstream JTC will have to be updated first, as we would need the state as a member variable of the base class. Fixing this here would make merging upstream later a lot more complicated.
1 parent 0a7cb0c commit b0e321f

File tree

1 file changed

+4
-0
lines changed

1 file changed

+4
-0
lines changed

ur_controllers/src/scaled_joint_trajectory_controller.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -336,10 +336,14 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
336336
}
337337

338338
// TODO(fmauch): Remove once merged upstream
339+
340+
#pragma GCC diagnostic push
341+
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
339342
if (state_publisher_->trylock()) {
340343
state_publisher_->msg_.speed_scaling_factor = scaling_factor_;
341344
state_publisher_->unlock();
342345
}
346+
#pragma GCC diagnostic pop
343347
// end remove once merged upstream
344348

345349
publish_state(time, state_desired_, state_current_, state_error_);

0 commit comments

Comments
 (0)