Skip to content

Commit 7a009e0

Browse files
committed
Add test for cbg getting reset
Signed-off-by: Michael Carroll <[email protected]>
1 parent 9c00772 commit 7a009e0

File tree

2 files changed

+141
-0
lines changed

2 files changed

+141
-0
lines changed

rclcpp/test/rclcpp/CMakeLists.txt

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -473,6 +473,15 @@ if(TARGET test_executors)
473473
target_link_libraries(test_executors_timer_cancel_behavior ${PROJECT_NAME} ${rosgraph_msgs_TARGETS})
474474
endif()
475475

476+
ament_add_gtest(
477+
test_executors_callback_group_behavior
478+
executors/test_executors_callback_group_behavior.cpp
479+
APPEND_LIBRARY_DIRS "${append_library_dirs}"
480+
TIMEOUT 180)
481+
if(TARGET test_executors)
482+
target_link_libraries(test_executors_callback_group_behavior ${PROJECT_NAME})
483+
endif()
484+
476485
ament_add_gtest(
477486
test_executors_intraprocess
478487
executors/test_executors_intraprocess.cpp
Lines changed: 132 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,132 @@
1+
// Copyright 2017 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
/**
16+
* This test checks all implementations of rclcpp::executor to check they pass they basic API
17+
* tests. Anything specific to any executor in particular should go in a separate test file.
18+
*/
19+
20+
#include <gtest/gtest.h>
21+
22+
#include <chrono>
23+
#include <rclcpp/callback_group.hpp>
24+
#include <rclcpp/executor.hpp>
25+
#include <rclcpp/node.hpp>
26+
#include "rclcpp/any_subscription_callback.hpp"
27+
28+
29+
class CustomExecutor: public rclcpp::Executor
30+
{
31+
public:
32+
explicit CustomExecutor(const rclcpp::ExecutorOptions & options = rclcpp::ExecutorOptions())
33+
: rclcpp::Executor(options)
34+
{
35+
}
36+
37+
~CustomExecutor() override = default;
38+
39+
void spin() override {};
40+
41+
void collect() {
42+
this->collect_entities();
43+
}
44+
45+
void wait() {
46+
this->wait_for_work(std::chrono::milliseconds(10));
47+
}
48+
49+
size_t collected_timers() const {
50+
return this->current_collection_.timers.size();
51+
}
52+
53+
rclcpp::AnyExecutable next() {
54+
rclcpp::AnyExecutable ret;
55+
this->get_next_ready_executable(ret);
56+
return ret;
57+
}
58+
};
59+
60+
61+
TEST(TestCallbackGroup, ValidCbg)
62+
{
63+
rclcpp::init(0, nullptr);
64+
65+
// Create a timer associated with a callback group
66+
auto node = std::make_shared<rclcpp::Node>("node");
67+
68+
// Add the callback group to the executor
69+
auto executor = CustomExecutor();
70+
executor.add_node(node);
71+
executor.spin_all(std::chrono::milliseconds(10));
72+
73+
auto cbg = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, true);
74+
auto timer = node->create_wall_timer(std::chrono::milliseconds(1), [](){}, cbg);
75+
executor.add_callback_group(cbg, node->get_node_base_interface());
76+
77+
executor.spin_all(std::chrono::milliseconds(10));
78+
79+
// Collect the entities
80+
executor.collect();
81+
EXPECT_EQ(1u, executor.collected_timers());
82+
83+
executor.wait();
84+
auto next_executable = executor.next();
85+
EXPECT_NE(nullptr, next_executable.timer);
86+
EXPECT_NE(nullptr, next_executable.callback_group);
87+
88+
EXPECT_EQ(nullptr, next_executable.client);
89+
EXPECT_EQ(nullptr, next_executable.service);
90+
EXPECT_EQ(nullptr, next_executable.subscription);
91+
EXPECT_EQ(nullptr, next_executable.waitable);
92+
EXPECT_EQ(nullptr, next_executable.data);
93+
94+
rclcpp::shutdown();
95+
}
96+
97+
TEST(TestCallbackGroup, InvalidCbg)
98+
{
99+
rclcpp::init(0, nullptr);
100+
101+
// Create a timer associated with a callback group
102+
auto node = std::make_shared<rclcpp::Node>("node");
103+
104+
// Add the callback group to the executor
105+
auto executor = CustomExecutor();
106+
executor.add_node(node);
107+
executor.spin_all(std::chrono::milliseconds(10));
108+
109+
auto cbg = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, true);
110+
auto timer = node->create_wall_timer(std::chrono::milliseconds(1), [](){}, cbg);
111+
executor.add_callback_group(cbg, node->get_node_base_interface());
112+
113+
executor.spin_all(std::chrono::milliseconds(10));
114+
115+
// Collect the entities
116+
executor.collect();
117+
EXPECT_EQ(1u, executor.collected_timers());
118+
119+
cbg.reset();
120+
executor.wait();
121+
auto next_executable = executor.next();
122+
EXPECT_EQ(nullptr, next_executable.timer);
123+
EXPECT_EQ(nullptr, next_executable.callback_group);
124+
125+
EXPECT_EQ(nullptr, next_executable.client);
126+
EXPECT_EQ(nullptr, next_executable.service);
127+
EXPECT_EQ(nullptr, next_executable.subscription);
128+
EXPECT_EQ(nullptr, next_executable.waitable);
129+
EXPECT_EQ(nullptr, next_executable.data);
130+
131+
rclcpp::shutdown();
132+
}

0 commit comments

Comments
 (0)