Skip to content

Commit cf182e0

Browse files
mauropasseMauro Passerino
andauthored
Add test_actions & test_transient_local (#157)
Co-authored-by: Mauro Passerino <[email protected]>
1 parent 9e816ed commit cf182e0

File tree

4 files changed

+272
-2
lines changed

4 files changed

+272
-2
lines changed

rclcpp_action/CMakeLists.txt

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@ find_package(rcl_action REQUIRED)
99
find_package(test_msgs REQUIRED)
1010
find_package(rcpputils REQUIRED)
1111
find_package(rosidl_runtime_c REQUIRED)
12+
find_package(std_msgs REQUIRED)
1213

1314
# Default to C++17
1415
if(NOT CMAKE_CXX_STANDARD)
@@ -86,6 +87,29 @@ if(BUILD_TESTING)
8687

8788
add_subdirectory(test/benchmark)
8889

90+
ament_add_gtest(test_ros2_actions test/test_actions.cpp TIMEOUT 180)
91+
if(TARGET test_ros2_actions)
92+
ament_target_dependencies(test_ros2_actions
93+
"test_msgs"
94+
"rclcpp"
95+
)
96+
target_link_libraries(test_ros2_actions
97+
${PROJECT_NAME}
98+
mimick
99+
)
100+
endif()
101+
102+
ament_add_gtest(test_transient_local test/test_transient_local.cpp TIMEOUT 180)
103+
if(TARGET test_transient_local)
104+
ament_target_dependencies(test_transient_local
105+
"std_msgs"
106+
)
107+
target_link_libraries(test_transient_local
108+
${PROJECT_NAME}
109+
mimick
110+
)
111+
endif()
112+
89113
ament_add_gtest(test_client test/test_client.cpp TIMEOUT 180)
90114
if(TARGET test_client)
91115
ament_target_dependencies(test_client

rclcpp_action/include/rclcpp_action/server.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -675,7 +675,7 @@ class Server : public ServerBase, public std::enable_shared_from_this<Server<Act
675675
rclcpp::get_logger("rclcpp_action"),
676676
"Action server can't send result response, missing IPC Action client: %s. "
677677
"Will do inter-process publish",
678-
this->action_name_);
678+
this->action_name_.c_str());
679679

680680
return true;
681681
}

rclcpp_action/test/test_actions.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,6 @@
55
#include <thread>
66

77
#include <rclcpp/executors/single_threaded_executor.hpp>
8-
#include <rclcpp/executors/static_single_threaded_executor.hpp>
98
#include <rclcpp/experimental/executors/events_executor/events_executor.hpp>
109
#include <rclcpp/experimental/executors/events_executor/lock_free_events_queue.hpp>
1110
#include <rclcpp_action/client_goal_handle.hpp>
@@ -19,6 +18,7 @@ using GoalHandleFibonacci = typename rclcpp_action::ServerGoalHandle<Fibonacci>;
1918
using GoalHandleSharedPtr = typename std::shared_ptr<GoalHandleFibonacci>;
2019

2120
using rclcpp::experimental::executors::EventsExecutor;
21+
using rclcpp::executors::SingleThreadedExecutor;
2222

2323
// Define a structure to hold test info and utilities
2424
class TestInfo
Lines changed: 246 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,246 @@
1+
// Copyright 2024 iRobot Corporation. All Rights Reserved.
2+
3+
#include <gtest/gtest.h>
4+
5+
#include <chrono>
6+
#include <thread>
7+
8+
#include <rclcpp/experimental/executors/events_executor/events_executor.hpp>
9+
#include <rclcpp/experimental/executors/events_executor/lock_free_events_queue.hpp>
10+
#include <rclcpp/node.hpp>
11+
#include <rclcpp/publisher.hpp>
12+
#include <rclcpp/subscription.hpp>
13+
#include <std_msgs/msg/empty.hpp>
14+
15+
struct transient_local_test_data_t
16+
{
17+
// Whether the publisher should use IPC
18+
bool pub_use_ipc {false};
19+
// How many early subscribers and whether they should use IPC
20+
std::vector<bool> early_subs_use_ipc {};
21+
// How many late subscribers and whether they should use IPC
22+
std::vector<bool> late_subs_use_ipc {};
23+
};
24+
25+
static std::string to_string(
26+
const std::vector<bool> & bool_vec,
27+
const std::string & property_name)
28+
{
29+
if (bool_vec.empty()) {
30+
return "NONE;";
31+
}
32+
33+
std::string result;
34+
for (bool b : bool_vec) {
35+
if (!b) {
36+
result += "Non-";
37+
}
38+
result += property_name + ", ";
39+
}
40+
41+
return result;
42+
}
43+
44+
class TransientLocalPermutationTest
45+
: public testing::Test, public testing::WithParamInterface<transient_local_test_data_t>
46+
{
47+
public:
48+
void SetUp() override
49+
{
50+
rclcpp::init(0, nullptr);
51+
auto p = GetParam();
52+
std::cout << "Test permutation: { "
53+
<< (p.pub_use_ipc ? "IPC Publisher, " : "Non-IPC Publisher, ")
54+
<< "Early: " << to_string(p.early_subs_use_ipc, "IPC Sub")
55+
<< " Late: " << to_string(p.late_subs_use_ipc, "IPC Sub")
56+
<< " }"<< std::endl;
57+
}
58+
59+
void TearDown() override
60+
{
61+
rclcpp::shutdown();
62+
}
63+
};
64+
65+
INSTANTIATE_TEST_SUITE_P(
66+
EarlySubsOnlyTest,
67+
TransientLocalPermutationTest,
68+
testing::Values(
69+
///// tests with only 1 early sub; not very interesting but let's run them
70+
// non-ipc pub, 1 early non-ipc sub
71+
transient_local_test_data_t{false, {false}, {}},
72+
// non-ipc pub, 1 early ipc sub
73+
transient_local_test_data_t{false, {true}, {}},
74+
// ipc pub, 1 early non-ipc sub
75+
transient_local_test_data_t{true, {false}, {}},
76+
// ipc pub, 1 early ipc sub
77+
transient_local_test_data_t{true, {true}, {}}
78+
));
79+
80+
INSTANTIATE_TEST_SUITE_P(
81+
LateSubsOnlyTest,
82+
TransientLocalPermutationTest,
83+
testing::Values(
84+
///// tests with only 1 late sub
85+
// non-ipc pub, non-ipc late sub
86+
transient_local_test_data_t{false, {}, {false}},
87+
// non-ipc pub, ipc late sub
88+
transient_local_test_data_t{false, {}, {true}},
89+
// ipc pub, non-ipc late sub
90+
transient_local_test_data_t{true, {}, {false}},
91+
// ipc pub, ipc late sub
92+
transient_local_test_data_t{true, {}, {true}},
93+
///// tests with late mixed subscriptions
94+
// non-ipc pub, mixed late subs
95+
transient_local_test_data_t{false, {}, {true, false}},
96+
// ipc pub, mixed late subs
97+
transient_local_test_data_t{true, {}, {true, false}}
98+
));
99+
100+
INSTANTIATE_TEST_SUITE_P(
101+
EarlyAndLateSubsTest,
102+
TransientLocalPermutationTest,
103+
testing::Values(
104+
///// tests with early and late subscriptions
105+
// non-ipc pub, 1 non-ipc early sub, 1 non-ipc late sub
106+
transient_local_test_data_t{false, {false}, {false}},
107+
// non-ipc pub, 1 non-ipc early sub, 1 ipc late sub
108+
transient_local_test_data_t{false, {false}, {true}},
109+
// non-ipc pub, 1 non-ipc early sub, mixed late sub
110+
transient_local_test_data_t{false, {false}, {true, false}},
111+
// non-ipc pub, 1 ipc early sub, 1 non-ipc late sub
112+
transient_local_test_data_t{false, {true}, {false}},
113+
// non-ipc pub, 1 ipc early sub, 1 ipc late sub
114+
transient_local_test_data_t{false, {true}, {true}},
115+
// non-ipc pub, 1 ipc early sub, mixed late sub
116+
transient_local_test_data_t{false, {true}, {true, false}},
117+
// ipc pub, 1 non-ipc early sub, 1 non-ipc late sub
118+
transient_local_test_data_t{true, {false}, {false}},
119+
// ipc pub, 1 non-ipc early sub, 1 ipc late sub
120+
transient_local_test_data_t{true, {false}, {true}},
121+
// ipc pub, 1 non-ipc early sub, mixed late sub
122+
transient_local_test_data_t{true, {false}, {true, false}},
123+
// ipc pub, 1 ipc early sub, 1 non-ipc late sub
124+
transient_local_test_data_t{true, {true}, {false}},
125+
// ipc pub, 1 ipc early sub, 1 ipc late sub
126+
transient_local_test_data_t{true, {true}, {true}},
127+
// ipc pub, 1 ipc early sub, mixed late sub
128+
transient_local_test_data_t{true, {true}, {true, false}}
129+
));
130+
131+
struct sub_data_t
132+
{
133+
std::string id {};
134+
std::atomic<bool> msg_received {false};
135+
};
136+
137+
TEST_P(TransientLocalPermutationTest, PublishWithNoSubs)
138+
{
139+
auto test_data = GetParam();
140+
141+
auto pub_options = rclcpp::NodeOptions().use_intra_process_comms(test_data.pub_use_ipc);
142+
auto pub_node = rclcpp::Node::make_shared("pub_node", pub_options);
143+
144+
auto publisher = rclcpp::create_publisher<std_msgs::msg::Empty>(
145+
pub_node,
146+
"test_topic",
147+
rclcpp::QoS(10).transient_local());
148+
149+
auto sub_node = rclcpp::Node::make_shared("sub_node");
150+
151+
// Add nodes to the executor
152+
auto events_queue = std::make_unique<rclcpp::experimental::executors::LockFreeEventsQueue>();
153+
154+
auto executor = std::make_unique<rclcpp::experimental::executors::EventsExecutor>(std::move(events_queue), false, rclcpp::ExecutorOptions());
155+
156+
executor->add_node(pub_node);
157+
executor->add_node(sub_node);
158+
auto executor_thread = std::thread([&](){ executor->spin(); });
159+
160+
while (!executor->is_spinning()) {
161+
std::this_thread::sleep_for(std::chrono::milliseconds(1));
162+
}
163+
164+
std::vector<std::shared_ptr<sub_data_t>> test_subs_data;
165+
std::vector<std::shared_ptr<rclcpp::SubscriptionBase>> test_subs;
166+
167+
auto build_subs_from_vec = [&test_subs_data, &test_subs, sub_node=sub_node](
168+
const std::vector<bool> & subs_use_ipc,
169+
const std::string & prefix)
170+
{
171+
for (size_t i = 0; i < subs_use_ipc.size(); i++) {
172+
bool use_ipc = subs_use_ipc[i];
173+
174+
auto sub_data = std::make_shared<sub_data_t>();
175+
176+
sub_data->id = prefix + "_" + std::to_string(i) +"_with_" + (use_ipc ? "ipc" : "no-ipc");
177+
178+
auto sub_options = rclcpp::SubscriptionOptions();
179+
sub_options.use_intra_process_comm = use_ipc ? rclcpp::IntraProcessSetting::Enable : rclcpp::IntraProcessSetting::Disable;
180+
auto sub = rclcpp::create_subscription<std_msgs::msg::Empty>(
181+
sub_node,
182+
"test_topic",
183+
rclcpp::QoS(10).transient_local(),
184+
[sub_data=sub_data](std_msgs::msg::Empty::ConstSharedPtr) { sub_data->msg_received = true; },
185+
sub_options);
186+
187+
std::cout<<"Created " << sub_data->id << std::endl;
188+
test_subs_data.push_back(sub_data);
189+
test_subs.push_back(sub);
190+
}
191+
};
192+
193+
// Create early subscriptions
194+
build_subs_from_vec(test_data.early_subs_use_ipc, "early");
195+
196+
// Wait for discovery of early subs (to ensure that they are effectively "early")
197+
auto start_time = std::chrono::high_resolution_clock::now();
198+
while (std::chrono::high_resolution_clock::now() - start_time < std::chrono::seconds(10))
199+
{
200+
if (publisher->get_subscription_count() == test_subs.size()) {
201+
break;
202+
}
203+
std::this_thread::sleep_for(std::chrono::milliseconds(2));
204+
}
205+
ASSERT_EQ(publisher->get_subscription_count(), test_subs.size());
206+
207+
// Publish the message
208+
auto msg = std::make_unique<std_msgs::msg::Empty>();
209+
publisher->publish(std::move(msg));
210+
211+
// Create late subscriptions
212+
build_subs_from_vec(test_data.late_subs_use_ipc, "late");
213+
214+
// Run until all subs have received a message or we timeout
215+
start_time = std::chrono::high_resolution_clock::now();
216+
while (std::chrono::high_resolution_clock::now() - start_time < std::chrono::seconds(20))
217+
{
218+
bool done = true;
219+
for (const auto & data : test_subs_data) {
220+
// This sub didn't get a message, so go to next iteration oft
221+
if (!data->msg_received) {
222+
done = false;
223+
break;
224+
}
225+
}
226+
227+
if (done) {
228+
break;
229+
}
230+
std::this_thread::sleep_for(std::chrono::milliseconds(2));
231+
}
232+
233+
executor->cancel();
234+
executor_thread.join();
235+
236+
// Verify that all subs received data
237+
for (const auto & data : test_subs_data) {
238+
EXPECT_TRUE(data->msg_received) << data->id << " didn't receive a message";
239+
}
240+
}
241+
242+
int main(int argc, char **argv)
243+
{
244+
::testing::InitGoogleTest(&argc, argv);
245+
return RUN_ALL_TESTS();
246+
}

0 commit comments

Comments
 (0)