Skip to content

Commit

Permalink
Refactor and split test_service into test_{service,client} (#144)
Browse files Browse the repository at this point in the history
Signed-off-by: Christophe Bedard <[email protected]>
  • Loading branch information
christophebedard authored Nov 11, 2024
1 parent 5c0c36f commit f1e79eb
Show file tree
Hide file tree
Showing 5 changed files with 154 additions and 217 deletions.
1 change: 1 addition & 0 deletions test_tracetools/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -203,6 +203,7 @@ if(BUILD_TESTING)
# Tests to run with the default rmw implementation, which should not matter
set(_test_tracetools_pytest_tests
test/test_buffer.py
test/test_client.py
test/test_executor.py
test/test_intra.py
test/test_intra_pub_sub.py
Expand Down
76 changes: 19 additions & 57 deletions test_tracetools/src/test_service_ping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,71 +19,33 @@
#include "std_srvs/srv/empty.hpp"
#include "test_tracetools/mark_process.hpp"

using namespace std::chrono_literals;

#define NODE_NAME "test_service_ping"
#define SERVICE_NAME "pong"
#define CLIENT_NAME "ping"

class PingNode : public rclcpp::Node
{
public:
explicit PingNode(rclcpp::NodeOptions options)
: Node(NODE_NAME, options)
{
srv_ = this->create_service<std_srvs::srv::Empty>(
SERVICE_NAME,
std::bind(
&PingNode::service_callback,
this,
std::placeholders::_1,
std::placeholders::_2,
std::placeholders::_3));
client_ = this->create_client<std_srvs::srv::Empty>(
CLIENT_NAME);
timer_ = this->create_wall_timer(
500ms,
std::bind(&PingNode::timer_callback, this));
}

private:
void service_callback(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<std_srvs::srv::Empty::Request> request,
const std::shared_ptr<std_srvs::srv::Empty::Response> response)
{
(void)request_header;
(void)request;
(void)response;
RCLCPP_INFO(this->get_logger(), "got request");
rclcpp::shutdown();
}

void timer_callback()
{
auto req = std::make_shared<std_srvs::srv::Empty::Request>();
client_->async_send_request(req);
}

rclcpp::Service<std_srvs::srv::Empty>::SharedPtr srv_;
rclcpp::Client<std_srvs::srv::Empty>::SharedPtr client_;
rclcpp::TimerBase::SharedPtr timer_;
};

int main(int argc, char * argv[])
{
test_tracetools::mark_trace_test_process();

rclcpp::init(argc, argv);

rclcpp::executors::SingleThreadedExecutor exec;
auto ping_node = std::make_shared<PingNode>(rclcpp::NodeOptions());
exec.add_node(ping_node);
auto node = rclcpp::Node::make_shared("test_service_ping");

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

// Will actually be called inside the node's service callback
auto request = std::make_shared<std_srvs::srv::Empty::Request>();
auto result_future = client->async_send_request(request);
RCLCPP_INFO(node->get_logger(), "sent request");
if (rclcpp::spin_until_future_complete(node, result_future) !=
rclcpp::FutureReturnCode::SUCCESS)
{
client->remove_pending_request(result_future);
return 1;
}
auto result = result_future.get();
RCLCPP_INFO(node->get_logger(), "got response");
rclcpp::shutdown();
return 0;
}
61 changes: 16 additions & 45 deletions test_tracetools/src/test_service_pong.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,60 +18,31 @@
#include "std_srvs/srv/empty.hpp"
#include "test_tracetools/mark_process.hpp"

#define NODE_NAME "test_service_pong"
#define SERVICE_NAME "ping"
#define CLIENT_NAME "pong"

class PongNode : public rclcpp::Node
{
public:
explicit PongNode(rclcpp::NodeOptions options)
: Node(NODE_NAME, options)
{
srv_ = this->create_service<std_srvs::srv::Empty>(
SERVICE_NAME,
std::bind(
&PongNode::service_callback,
this,
std::placeholders::_1,
std::placeholders::_2,
std::placeholders::_3));
client_ = this->create_client<std_srvs::srv::Empty>(CLIENT_NAME);
}

private:
void service_callback(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<std_srvs::srv::Empty::Request> request,
const std::shared_ptr<std_srvs::srv::Empty::Response> response)
{
(void)request_header;
(void)request;
(void)response;
RCLCPP_INFO(this->get_logger(), "got request");
auto req = std::make_shared<std_srvs::srv::Empty::Request>();
client_->async_send_request(req);
rclcpp::shutdown();
}

rclcpp::Service<std_srvs::srv::Empty>::SharedPtr srv_;
rclcpp::Client<std_srvs::srv::Empty>::SharedPtr client_;
};

int main(int argc, char * argv[])
{
test_tracetools::mark_trace_test_process();

rclcpp::init(argc, argv);

rclcpp::executors::SingleThreadedExecutor exec;
auto pong_node = std::make_shared<PongNode>(rclcpp::NodeOptions());
exec.add_node(pong_node);
auto node = rclcpp::Node::make_shared("test_service_pong");

printf("spinning\n");
auto client = node->create_service<std_srvs::srv::Empty>(
"ping",
[&](const std::shared_ptr<rclcpp::Service<std_srvs::srv::Empty>> service,
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<std_srvs::srv::Empty::Request> request) {
(void)request;
RCLCPP_INFO(node->get_logger(), "got request");
std_srvs::srv::Empty::Response response;
service->send_response(*request_header, response);
RCLCPP_INFO(node->get_logger(), "sent response");
// Stop executor after this callback is done
exec.cancel();
});

exec.add_node(node);
exec.spin();

// Will actually be called inside the node's service callback
rclcpp::shutdown();
return 0;
}
76 changes: 76 additions & 0 deletions test_tracetools/test/test_client.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
# Copyright 2024 Apex.AI, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import unittest

from tracetools_test.case import TraceTestCase
from tracetools_trace.tools import tracepoints as tp
from tracetools_trace.tools.lttng import is_lttng_installed


@unittest.skipIf(not is_lttng_installed(minimum_version='2.9.0'), 'LTTng is required')
class TestClient(TraceTestCase):

def __init__(self, *args) -> None:
super().__init__(
*args,
session_name_prefix='session-test-client',
events_ros=[
tp.rcl_node_init,
tp.rcl_client_init,
],
package='test_tracetools',
nodes=['test_service_ping', 'test_service_pong'],
)

def test_all(self):
# Check events as set
self.assertEventsSet(self._events_ros)

# Check fields
client_init_events = self.get_events_with_name(tp.rcl_client_init)

for event in client_init_events:
self.assertValidHandle(event, ['client_handle', 'node_handle', 'rmw_client_handle'])
self.assertStringFieldNotEmpty(event, 'service_name')

# Find node event
node_init_events = self.get_events_with_name(tp.rcl_node_init)
# The test_service_ping node is the one that has the client
test_node_init_event = self.get_event_with_field_value_and_assert(
'node_name',
'test_service_ping',
node_init_events,
allow_multiple=False,
)
node_handle = self.get_field(test_node_init_event, 'node_handle')

# Find client init event and check that the node handle matches
test_client_init_event = self.get_event_with_field_value_and_assert(
'service_name',
'/ping',
client_init_events,
allow_multiple=False,
)
self.assertFieldEquals(test_client_init_event, 'node_handle', node_handle)

# Check events order
self.assertEventOrder([
test_node_init_event,
test_client_init_event,
])


if __name__ == '__main__':
unittest.main()
Loading

0 comments on commit f1e79eb

Please sign in to comment.