Skip to content

Commit 3310f9e

Browse files
authored
Fix warnings on Windows. (#2692)
For reasons I admit I do not understand, the deprecation warnings for StaticSingleThreadedExecutor on Windows happen when we construct a shared_ptr for it in the tests. If we construct a regular object, then it is fine. Luckily this test does not require a shared_ptr, so just make it a regular object here, which rixes the warning. While we are in here, make all of the tests camel case to be consistent. Signed-off-by: Chris Lalancette <[email protected]>
1 parent 785a70d commit 3310f9e

File tree

1 file changed

+11
-10
lines changed

1 file changed

+11
-10
lines changed

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 11 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -388,7 +388,7 @@ to_nanoseconds_helper(DurationT duration)
388388
// - works nominally (it can execute entities)
389389
// - it can execute multiple items at once
390390
// - it does not wait for work to be available before returning
391-
TYPED_TEST(TestExecutors, spin_some)
391+
TYPED_TEST(TestExecutors, spinSome)
392392
{
393393
using ExecutorType = TypeParam;
394394

@@ -484,7 +484,7 @@ TYPED_TEST(TestExecutors, spin_some)
484484
// do not properly implement max_duration (it seems), so disable this test
485485
// for them in the meantime.
486486
// see: https://github.com/ros2/rclcpp/issues/2462
487-
TYPED_TEST(TestExecutorsStable, spin_some_max_duration)
487+
TYPED_TEST(TestExecutorsStable, spinSomeMaxDuration)
488488
{
489489
using ExecutorType = TypeParam;
490490

@@ -834,7 +834,7 @@ TEST(TestExecutors, testSpinWithNonDefaultContext)
834834
rclcpp::shutdown(non_default_context);
835835
}
836836

837-
TYPED_TEST(TestExecutors, release_ownership_entity_after_spinning_cancel)
837+
TYPED_TEST(TestExecutors, releaseOwnershipEntityAfterSpinningCancel)
838838
{
839839
using ExecutorType = TypeParam;
840840
ExecutorType executor;
@@ -870,19 +870,20 @@ TYPED_TEST(TestExecutors, testRaceDropCallbackGroupFromSecondThread)
870870
}
871871

872872
// Create an executor
873-
auto executor = std::make_shared<ExecutorType>();
874-
executor->add_node(this->node);
873+
ExecutorType executor;
874+
executor.add_node(this->node);
875875

876876
// Start spinning
877877
auto executor_thread = std::thread(
878-
[executor]() {
879-
executor->spin();
878+
[&executor]() {
879+
executor.spin();
880880
});
881881

882882
// As the problem is a race, we do this multiple times,
883883
// to raise our chances of hitting the problem
884-
for(size_t i = 0; i < 10; i++) {
885-
auto cg = this->node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
884+
for (size_t i = 0; i < 10; i++) {
885+
auto cg = this->node->create_callback_group(
886+
rclcpp::CallbackGroupType::MutuallyExclusive);
886887
auto timer = this->node->create_timer(1s, [] {}, cg);
887888
// sleep a bit, so that the spin thread can pick up the callback group
888889
// and add it to the executor
@@ -893,6 +894,6 @@ TYPED_TEST(TestExecutors, testRaceDropCallbackGroupFromSecondThread)
893894
// If the executor has a race, we will experience a segfault at this point.
894895
}
895896

896-
executor->cancel();
897+
executor.cancel();
897898
executor_thread.join();
898899
}

0 commit comments

Comments
 (0)