2424
2525#include " rcl/service.h"
2626
27- #include " rclcpp /srv/mock .hpp"
28- #include " rclcpp /srv/mock .h"
27+ #include " test_msgs /srv/empty .hpp"
28+ #include " test_msgs /srv/empty .h"
2929
3030class TestExternallyDefinedServices : public ::testing::Test
3131{
@@ -38,36 +38,34 @@ class TestExternallyDefinedServices : public ::testing::Test
3838
3939void
4040callback (
41- const std::shared_ptr<rclcpp ::srv::Mock ::Request>/* req*/ ,
42- std::shared_ptr<rclcpp ::srv::Mock ::Response>/* resp*/ )
41+ const std::shared_ptr<test_msgs ::srv::Empty ::Request>/* req*/ ,
42+ std::shared_ptr<test_msgs ::srv::Empty ::Response>/* resp*/ )
4343{}
4444
4545TEST_F (TestExternallyDefinedServices, default_behavior) {
4646 auto node_handle = rclcpp::Node::make_shared (" base_node" );
4747
4848 try {
49- auto srv = node_handle->create_service <rclcpp::srv::Mock>(" test" ,
50- callback);
49+ auto srv = node_handle->create_service <test_msgs::srv::Empty>(" test" , callback);
5150 } catch (const std::exception &) {
5251 FAIL ();
5352 return ;
5453 }
5554 SUCCEED ();
5655}
5756
58-
5957TEST_F (TestExternallyDefinedServices, extern_defined_uninitialized) {
6058 auto node_handle = rclcpp::Node::make_shared (" base_node" );
6159
6260 // mock for externally defined service
6361 rcl_service_t service_handle = rcl_get_zero_initialized_service ();
6462
65- rclcpp::AnyServiceCallback<rclcpp ::srv::Mock > cb;
63+ rclcpp::AnyServiceCallback<test_msgs ::srv::Empty > cb;
6664
6765 // don't initialize the service
6866 // expect fail
6967 try {
70- rclcpp::Service<rclcpp ::srv::Mock >(
68+ rclcpp::Service<test_msgs ::srv::Empty >(
7169 node_handle->get_node_base_interface ()->get_shared_rcl_node_handle (),
7270 &service_handle, cb);
7371 } catch (const std::runtime_error &) {
@@ -85,7 +83,7 @@ TEST_F(TestExternallyDefinedServices, extern_defined_initialized) {
8583 rcl_service_t service_handle = rcl_get_zero_initialized_service ();
8684 rcl_service_options_t service_options = rcl_service_get_default_options ();
8785 const rosidl_service_type_support_t * ts =
88- rosidl_typesupport_cpp::get_service_type_support_handle<rclcpp ::srv::Mock >();
86+ rosidl_typesupport_cpp::get_service_type_support_handle<test_msgs ::srv::Empty >();
8987 rcl_ret_t ret = rcl_service_init (
9088 &service_handle,
9189 node_handle->get_node_base_interface ()->get_rcl_node_handle (),
@@ -95,10 +93,10 @@ TEST_F(TestExternallyDefinedServices, extern_defined_initialized) {
9593 return ;
9694 }
9795
98- rclcpp::AnyServiceCallback<rclcpp ::srv::Mock > cb;
96+ rclcpp::AnyServiceCallback<test_msgs ::srv::Empty > cb;
9997
10098 try {
101- rclcpp::Service<rclcpp ::srv::Mock >(
99+ rclcpp::Service<test_msgs ::srv::Empty >(
102100 node_handle->get_node_base_interface ()->get_shared_rcl_node_handle (),
103101 &service_handle, cb);
104102 } catch (const std::runtime_error &) {
@@ -125,7 +123,7 @@ TEST_F(TestExternallyDefinedServices, extern_defined_destructor) {
125123 rcl_service_t service_handle = rcl_get_zero_initialized_service ();
126124 rcl_service_options_t service_options = rcl_service_get_default_options ();
127125 const rosidl_service_type_support_t * ts =
128- rosidl_typesupport_cpp::get_service_type_support_handle<rclcpp ::srv::Mock >();
126+ rosidl_typesupport_cpp::get_service_type_support_handle<test_msgs ::srv::Empty >();
129127 rcl_ret_t ret = rcl_service_init (
130128 &service_handle,
131129 node_handle->get_node_base_interface ()->get_rcl_node_handle (),
@@ -134,11 +132,11 @@ TEST_F(TestExternallyDefinedServices, extern_defined_destructor) {
134132 FAIL ();
135133 return ;
136134 }
137- rclcpp::AnyServiceCallback<rclcpp ::srv::Mock > cb;
135+ rclcpp::AnyServiceCallback<test_msgs ::srv::Empty > cb;
138136
139137 {
140138 // Call constructor
141- rclcpp::Service<rclcpp ::srv::Mock > srv_cpp (
139+ rclcpp::Service<test_msgs ::srv::Empty > srv_cpp (
142140 node_handle->get_node_base_interface ()->get_shared_rcl_node_handle (),
143141 &service_handle, cb);
144142 // Call destructor
0 commit comments