Skip to content

Commit e52c955

Browse files
Refactor and split test_service into test_{service,client}
Signed-off-by: Christophe Bedard <[email protected]>
1 parent 5c0c36f commit e52c955

File tree

5 files changed

+154
-217
lines changed

5 files changed

+154
-217
lines changed

Diff for: test_tracetools/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -203,6 +203,7 @@ if(BUILD_TESTING)
203203
# Tests to run with the default rmw implementation, which should not matter
204204
set(_test_tracetools_pytest_tests
205205
test/test_buffer.py
206+
test/test_client.py
206207
test/test_executor.py
207208
test/test_intra.py
208209
test/test_intra_pub_sub.py

Diff for: test_tracetools/src/test_service_ping.cpp

+19-57
Original file line numberDiff line numberDiff line change
@@ -19,71 +19,33 @@
1919
#include "std_srvs/srv/empty.hpp"
2020
#include "test_tracetools/mark_process.hpp"
2121

22-
using namespace std::chrono_literals;
23-
24-
#define NODE_NAME "test_service_ping"
25-
#define SERVICE_NAME "pong"
26-
#define CLIENT_NAME "ping"
27-
28-
class PingNode : public rclcpp::Node
29-
{
30-
public:
31-
explicit PingNode(rclcpp::NodeOptions options)
32-
: Node(NODE_NAME, options)
33-
{
34-
srv_ = this->create_service<std_srvs::srv::Empty>(
35-
SERVICE_NAME,
36-
std::bind(
37-
&PingNode::service_callback,
38-
this,
39-
std::placeholders::_1,
40-
std::placeholders::_2,
41-
std::placeholders::_3));
42-
client_ = this->create_client<std_srvs::srv::Empty>(
43-
CLIENT_NAME);
44-
timer_ = this->create_wall_timer(
45-
500ms,
46-
std::bind(&PingNode::timer_callback, this));
47-
}
48-
49-
private:
50-
void service_callback(
51-
const std::shared_ptr<rmw_request_id_t> request_header,
52-
const std::shared_ptr<std_srvs::srv::Empty::Request> request,
53-
const std::shared_ptr<std_srvs::srv::Empty::Response> response)
54-
{
55-
(void)request_header;
56-
(void)request;
57-
(void)response;
58-
RCLCPP_INFO(this->get_logger(), "got request");
59-
rclcpp::shutdown();
60-
}
61-
62-
void timer_callback()
63-
{
64-
auto req = std::make_shared<std_srvs::srv::Empty::Request>();
65-
client_->async_send_request(req);
66-
}
67-
68-
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr srv_;
69-
rclcpp::Client<std_srvs::srv::Empty>::SharedPtr client_;
70-
rclcpp::TimerBase::SharedPtr timer_;
71-
};
72-
7322
int main(int argc, char * argv[])
7423
{
7524
test_tracetools::mark_trace_test_process();
7625

7726
rclcpp::init(argc, argv);
7827

79-
rclcpp::executors::SingleThreadedExecutor exec;
80-
auto ping_node = std::make_shared<PingNode>(rclcpp::NodeOptions());
81-
exec.add_node(ping_node);
28+
auto node = rclcpp::Node::make_shared("test_service_ping");
8229

83-
printf("spinning\n");
84-
exec.spin();
30+
auto client = node->create_client<std_srvs::srv::Empty>("ping");
31+
RCLCPP_INFO(node->get_logger(), "waiting for service");
32+
while (!client->wait_for_service(std::chrono::seconds(10))) {
33+
if (!rclcpp::ok()) {
34+
return 1;
35+
}
36+
}
8537

86-
// Will actually be called inside the node's service callback
38+
auto request = std::make_shared<std_srvs::srv::Empty::Request>();
39+
auto result_future = client->async_send_request(request);
40+
RCLCPP_INFO(node->get_logger(), "sent request");
41+
if (rclcpp::spin_until_future_complete(node, result_future) !=
42+
rclcpp::FutureReturnCode::SUCCESS)
43+
{
44+
client->remove_pending_request(result_future);
45+
return 1;
46+
}
47+
auto result = result_future.get();
48+
RCLCPP_INFO(node->get_logger(), "got response");
8749
rclcpp::shutdown();
8850
return 0;
8951
}

Diff for: test_tracetools/src/test_service_pong.cpp

+16-45
Original file line numberDiff line numberDiff line change
@@ -18,60 +18,31 @@
1818
#include "std_srvs/srv/empty.hpp"
1919
#include "test_tracetools/mark_process.hpp"
2020

21-
#define NODE_NAME "test_service_pong"
22-
#define SERVICE_NAME "ping"
23-
#define CLIENT_NAME "pong"
24-
25-
class PongNode : public rclcpp::Node
26-
{
27-
public:
28-
explicit PongNode(rclcpp::NodeOptions options)
29-
: Node(NODE_NAME, options)
30-
{
31-
srv_ = this->create_service<std_srvs::srv::Empty>(
32-
SERVICE_NAME,
33-
std::bind(
34-
&PongNode::service_callback,
35-
this,
36-
std::placeholders::_1,
37-
std::placeholders::_2,
38-
std::placeholders::_3));
39-
client_ = this->create_client<std_srvs::srv::Empty>(CLIENT_NAME);
40-
}
41-
42-
private:
43-
void service_callback(
44-
const std::shared_ptr<rmw_request_id_t> request_header,
45-
const std::shared_ptr<std_srvs::srv::Empty::Request> request,
46-
const std::shared_ptr<std_srvs::srv::Empty::Response> response)
47-
{
48-
(void)request_header;
49-
(void)request;
50-
(void)response;
51-
RCLCPP_INFO(this->get_logger(), "got request");
52-
auto req = std::make_shared<std_srvs::srv::Empty::Request>();
53-
client_->async_send_request(req);
54-
rclcpp::shutdown();
55-
}
56-
57-
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr srv_;
58-
rclcpp::Client<std_srvs::srv::Empty>::SharedPtr client_;
59-
};
60-
6121
int main(int argc, char * argv[])
6222
{
6323
test_tracetools::mark_trace_test_process();
6424

6525
rclcpp::init(argc, argv);
6626

6727
rclcpp::executors::SingleThreadedExecutor exec;
68-
auto pong_node = std::make_shared<PongNode>(rclcpp::NodeOptions());
69-
exec.add_node(pong_node);
28+
auto node = rclcpp::Node::make_shared("test_service_pong");
7029

71-
printf("spinning\n");
30+
auto client = node->create_service<std_srvs::srv::Empty>(
31+
"ping",
32+
[&](const std::shared_ptr<rclcpp::Service<std_srvs::srv::Empty>> service,
33+
const std::shared_ptr<rmw_request_id_t> request_header,
34+
const std::shared_ptr<std_srvs::srv::Empty::Request> request) {
35+
(void)request;
36+
RCLCPP_INFO(node->get_logger(), "got request");
37+
std_srvs::srv::Empty::Response response;
38+
service->send_response(*request_header, response);
39+
RCLCPP_INFO(node->get_logger(), "sent response");
40+
// Stop executor after this callback is done
41+
exec.cancel();
42+
});
43+
44+
exec.add_node(node);
7245
exec.spin();
73-
74-
// Will actually be called inside the node's service callback
7546
rclcpp::shutdown();
7647
return 0;
7748
}

Diff for: test_tracetools/test/test_client.py

+76
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,76 @@
1+
# Copyright 2024 Apex.AI, 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+
import unittest
16+
17+
from tracetools_test.case import TraceTestCase
18+
from tracetools_trace.tools import tracepoints as tp
19+
from tracetools_trace.tools.lttng import is_lttng_installed
20+
21+
22+
@unittest.skipIf(not is_lttng_installed(minimum_version='2.9.0'), 'LTTng is required')
23+
class TestClient(TraceTestCase):
24+
25+
def __init__(self, *args) -> None:
26+
super().__init__(
27+
*args,
28+
session_name_prefix='session-test-client',
29+
events_ros=[
30+
tp.rcl_node_init,
31+
tp.rcl_client_init,
32+
],
33+
package='test_tracetools',
34+
nodes=['test_service_ping', 'test_service_pong'],
35+
)
36+
37+
def test_all(self):
38+
# Check events as set
39+
self.assertEventsSet(self._events_ros)
40+
41+
# Check fields
42+
client_init_events = self.get_events_with_name(tp.rcl_client_init)
43+
44+
for event in client_init_events:
45+
self.assertValidHandle(event, ['client_handle', 'node_handle', 'rmw_client_handle'])
46+
self.assertStringFieldNotEmpty(event, 'service_name')
47+
48+
# Find node event
49+
node_init_events = self.get_events_with_name(tp.rcl_node_init)
50+
# The test_service_ping node is the one that has the client
51+
test_node_init_event = self.get_event_with_field_value_and_assert(
52+
'node_name',
53+
'test_service_ping',
54+
node_init_events,
55+
allow_multiple=False,
56+
)
57+
node_handle = self.get_field(test_node_init_event, 'node_handle')
58+
59+
# Find client init event and check that the node handle matches
60+
test_client_init_event = self.get_event_with_field_value_and_assert(
61+
'service_name',
62+
'/ping',
63+
client_init_events,
64+
allow_multiple=False,
65+
)
66+
self.assertFieldEquals(test_client_init_event, 'node_handle', node_handle)
67+
68+
# Check events order
69+
self.assertEventOrder([
70+
test_node_init_event,
71+
test_client_init_event,
72+
])
73+
74+
75+
if __name__ == '__main__':
76+
unittest.main()

0 commit comments

Comments
 (0)