Add service callback test
This commit is contained in:
parent
77645f2a52
commit
ce9d6eff95
4 changed files with 179 additions and 0 deletions
|
@ -58,6 +58,20 @@ if(BUILD_TESTING)
|
||||||
rclcpp
|
rclcpp
|
||||||
std_srvs
|
std_srvs
|
||||||
)
|
)
|
||||||
|
add_executable(test_service_ping
|
||||||
|
src/test_service_ping.cpp
|
||||||
|
)
|
||||||
|
ament_target_dependencies(test_service_ping
|
||||||
|
rclcpp
|
||||||
|
std_srvs
|
||||||
|
)
|
||||||
|
add_executable(test_service_pong
|
||||||
|
src/test_service_pong.cpp
|
||||||
|
)
|
||||||
|
ament_target_dependencies(test_service_pong
|
||||||
|
rclcpp
|
||||||
|
std_srvs
|
||||||
|
)
|
||||||
|
|
||||||
install(TARGETS
|
install(TARGETS
|
||||||
test_publisher
|
test_publisher
|
||||||
|
@ -66,6 +80,8 @@ if(BUILD_TESTING)
|
||||||
test_pong
|
test_pong
|
||||||
test_timer
|
test_timer
|
||||||
test_service
|
test_service
|
||||||
|
test_service_ping
|
||||||
|
test_service_pong
|
||||||
DESTINATION lib/${PROJECT_NAME}
|
DESTINATION lib/${PROJECT_NAME}
|
||||||
)
|
)
|
||||||
|
|
||||||
|
@ -79,6 +95,7 @@ if(BUILD_TESTING)
|
||||||
test/test_subscription_callback.py
|
test/test_subscription_callback.py
|
||||||
test/test_timer.py
|
test/test_timer.py
|
||||||
test/test_service.py
|
test/test_service.py
|
||||||
|
test/test_service_callback.py
|
||||||
)
|
)
|
||||||
|
|
||||||
foreach(_test_path ${_tracetools_test_pytest_tests})
|
foreach(_test_path ${_tracetools_test_pytest_tests})
|
||||||
|
|
68
tracetools_test/src/test_service_ping.cpp
Normal file
68
tracetools_test/src/test_service_ping.cpp
Normal file
|
@ -0,0 +1,68 @@
|
||||||
|
#include <memory>
|
||||||
|
#include <chrono>
|
||||||
|
|
||||||
|
#include "rclcpp/rclcpp.hpp"
|
||||||
|
#include "std_srvs/srv/empty.hpp"
|
||||||
|
|
||||||
|
using namespace std::chrono_literals;
|
||||||
|
|
||||||
|
|
||||||
|
class PingNode : public rclcpp::Node
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
PingNode(rclcpp::NodeOptions options) : Node("ping_node", options)
|
||||||
|
{
|
||||||
|
srv_ = this->create_service<std_srvs::srv::Empty>(
|
||||||
|
"pong",
|
||||||
|
std::bind(&PingNode::service_callback,
|
||||||
|
this,
|
||||||
|
std::placeholders::_1,
|
||||||
|
std::placeholders::_2,
|
||||||
|
std::placeholders::_3));
|
||||||
|
client_ = this->create_client<std_srvs::srv::Empty>(
|
||||||
|
"ping");
|
||||||
|
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[])
|
||||||
|
{
|
||||||
|
rclcpp::init(argc, argv);
|
||||||
|
|
||||||
|
rclcpp::executors::SingleThreadedExecutor exec;
|
||||||
|
auto ping_node = std::make_shared<PingNode>(rclcpp::NodeOptions());
|
||||||
|
exec.add_node(ping_node);
|
||||||
|
|
||||||
|
printf("spinning\n");
|
||||||
|
exec.spin();
|
||||||
|
|
||||||
|
// Will actually be called inside the node's service callback
|
||||||
|
rclcpp::shutdown();
|
||||||
|
return 0;
|
||||||
|
}
|
57
tracetools_test/src/test_service_pong.cpp
Normal file
57
tracetools_test/src/test_service_pong.cpp
Normal file
|
@ -0,0 +1,57 @@
|
||||||
|
#include <memory>
|
||||||
|
|
||||||
|
#include "rclcpp/rclcpp.hpp"
|
||||||
|
#include "std_srvs/srv/empty.hpp"
|
||||||
|
|
||||||
|
|
||||||
|
class PongNode : public rclcpp::Node
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
PongNode(rclcpp::NodeOptions options) : Node("pong_node", options)
|
||||||
|
{
|
||||||
|
srv_ = this->create_service<std_srvs::srv::Empty>(
|
||||||
|
"ping",
|
||||||
|
std::bind(&PongNode::service_callback,
|
||||||
|
this,
|
||||||
|
std::placeholders::_1,
|
||||||
|
std::placeholders::_2,
|
||||||
|
std::placeholders::_3));
|
||||||
|
client_ = this->create_client<std_srvs::srv::Empty>(
|
||||||
|
"pong");
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
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[])
|
||||||
|
{
|
||||||
|
rclcpp::init(argc, argv);
|
||||||
|
|
||||||
|
rclcpp::executors::SingleThreadedExecutor exec;
|
||||||
|
auto pong_node = std::make_shared<PongNode>(rclcpp::NodeOptions());
|
||||||
|
exec.add_node(pong_node);
|
||||||
|
|
||||||
|
printf("spinning\n");
|
||||||
|
exec.spin();
|
||||||
|
|
||||||
|
// Will actually be called inside the node's service callback
|
||||||
|
rclcpp::shutdown();
|
||||||
|
return 0;
|
||||||
|
}
|
37
tracetools_test/test/test_service_callback.py
Normal file
37
tracetools_test/test/test_service_callback.py
Normal file
|
@ -0,0 +1,37 @@
|
||||||
|
import unittest
|
||||||
|
from tracetools_test.utils import (
|
||||||
|
get_trace_event_names,
|
||||||
|
run_and_trace,
|
||||||
|
cleanup_trace,
|
||||||
|
)
|
||||||
|
|
||||||
|
BASE_PATH = '/tmp'
|
||||||
|
PKG = 'tracetools_test'
|
||||||
|
service_callback_events = [
|
||||||
|
'ros2:rclcpp_service_callback_start',
|
||||||
|
'ros2:rclcpp_service_callback_end',
|
||||||
|
]
|
||||||
|
|
||||||
|
class TestServiceCallback(unittest.TestCase):
|
||||||
|
|
||||||
|
def test_callback(self):
|
||||||
|
session_name_prefix = 'session-test-service-callback'
|
||||||
|
test_nodes = ['test_service_ping', 'test_service_pong']
|
||||||
|
|
||||||
|
exit_code, full_path = run_and_trace(BASE_PATH,
|
||||||
|
session_name_prefix,
|
||||||
|
service_callback_events,
|
||||||
|
None,
|
||||||
|
PKG,
|
||||||
|
test_nodes)
|
||||||
|
self.assertEqual(exit_code, 0)
|
||||||
|
|
||||||
|
trace_events = get_trace_event_names(full_path)
|
||||||
|
print(f'trace_events: {trace_events}')
|
||||||
|
self.assertSetEqual(set(service_callback_events), trace_events)
|
||||||
|
|
||||||
|
cleanup_trace(full_path)
|
||||||
|
|
||||||
|
|
||||||
|
if __name__ == '__main__':
|
||||||
|
unittest.main()
|
Loading…
Add table
Add a link
Reference in a new issue