Skip to content

Commit 9771561

Browse files
committed
Disable internal deprecation warning
We forward the deprecated setKeepalive method through the UrDriver which triggers a depracation warning. We disable it (for GCC) for this call.
1 parent 56ec4f4 commit 9771561

File tree

2 files changed

+7
-0
lines changed

2 files changed

+7
-0
lines changed

src/ur/ur_driver.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -665,7 +665,11 @@ void UrDriver::setKeepaliveCount(const uint32_t count)
665665
"set the "
666666
"read timeout in the write commands directly. This keepalive count will overwrite the timeout passed "
667667
"to the write functions.");
668+
// TODO: Remove 2027-05
669+
#pragma GCC diagnostic push
670+
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
668671
reverse_interface_->setKeepaliveCount(count);
672+
#pragma GCC diagnostic pop
669673
}
670674

671675
void UrDriver::resetRTDEClient(const std::vector<std::string>& output_recipe,

tests/test_reverse_interface.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -428,7 +428,10 @@ TEST_F(ReverseIntefaceTest, deprecated_set_keep_alive_count)
428428

429429
// Test that it works to set the keepalive count using the deprecated function
430430
int keep_alive_count = 10;
431+
#pragma GCC diagnostic push
432+
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
431433
reverse_interface_->setKeepaliveCount(keep_alive_count);
434+
#pragma GCC diagnostic pop
432435
int32_t expected_read_timeout = 20 * keep_alive_count;
433436

434437
urcl::vector6d_t pos = { 0, 0, 0, 0, 0, 0 };

0 commit comments

Comments
 (0)