forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathtest_type_support.cpp
More file actions
199 lines (175 loc) · 6.62 KB
/
test_type_support.cpp
File metadata and controls
199 lines (175 loc) · 6.62 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
// Copyright 2020 Open Source Robotics Foundation, 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.
#include <gtest/gtest.h>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/type_support_decl.hpp"
#include "test_msgs/msg/empty.hpp"
class TestTypeSupport : public ::testing::Test
{
public:
static void SetUpTestCase()
{
if (!rclcpp::ok()) {
rclcpp::init(0, nullptr);
}
}
static void TearDownTestCase()
{
rclcpp::shutdown();
}
::testing::AssertionResult test_type_support_init_fini(const rosidl_service_type_support_t * ts)
{
rcl_service_t service_handle = rcl_get_zero_initialized_service();
rcl_service_options_t service_options = rcl_service_get_default_options();
auto node_handle = node->get_node_base_interface()->get_rcl_node_handle();
rcl_ret_t ret = rcl_service_init(
&service_handle, node_handle, ts, "base_node_service", &service_options);
if (ret != RCL_RET_OK) {
return ::testing::AssertionFailure() <<
"Failed rcl_service_init with error string: " << rcl_get_error_string().str;
}
ret = rcl_service_fini(&service_handle, node_handle);
if (ret != RCL_RET_OK) {
return ::testing::AssertionFailure() <<
"Failed rcl_service_fini with error string: " << rcl_get_error_string().str;
}
return ::testing::AssertionSuccess();
}
protected:
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("my_node", "/ns");
};
const rcl_publisher_options_t PublisherOptions()
{
return rclcpp::PublisherOptionsWithAllocator<std::allocator<void>>().template
to_rcl_publisher_options<test_msgs::msg::Empty>(rclcpp::QoS(10));
}
// Auxiliary classes used to test rosidl_message_type_support_t getters
// defined in type_support.hpp
const rosidl_message_type_support_t * ts_parameter_event =
rclcpp::type_support::get_parameter_event_msg_type_support();
class TestTSParameterEvent : public rclcpp::PublisherBase
{
public:
explicit TestTSParameterEvent(rclcpp::Node * node)
: rclcpp::PublisherBase(
node->get_node_base_interface().get(),
"topicTSParameterEvent",
*ts_parameter_event,
PublisherOptions()) {}
};
const rosidl_message_type_support_t * ts_set_parameter_result =
rclcpp::type_support::get_set_parameters_result_msg_type_support();
class TestTSSetParameterResult : public rclcpp::PublisherBase
{
public:
explicit TestTSSetParameterResult(rclcpp::Node * node)
: rclcpp::PublisherBase(
node->get_node_base_interface().get(),
"topicTSSetParameterResult",
*ts_set_parameter_result,
PublisherOptions()) {}
};
const rosidl_message_type_support_t * ts_parameter_descriptor =
rclcpp::type_support::get_parameter_descriptor_msg_type_support();
class TestTSParameterDescriptor : public rclcpp::PublisherBase
{
public:
explicit TestTSParameterDescriptor(rclcpp::Node * node)
: rclcpp::PublisherBase(
node->get_node_base_interface().get(),
"topicTSParameterDescriptor",
*ts_parameter_descriptor,
PublisherOptions()) {}
};
const rosidl_message_type_support_t * ts_list_parameter_result =
rclcpp::type_support::get_list_parameters_result_msg_type_support();
class TestTSListParametersResult : public rclcpp::PublisherBase
{
public:
explicit TestTSListParametersResult(rclcpp::Node * node)
: rclcpp::PublisherBase(
node->get_node_base_interface().get(),
"topicTSListParametersResult",
*ts_list_parameter_result,
PublisherOptions()) {}
};
/*
Test that the publisher is created properly for different msg typesupport
*/
TEST_F(TestTypeSupport, basic_getters) {
{
auto publisher = TestTSParameterEvent(node.get());
std::shared_ptr<const rcl_publisher_t> publisher_handle = publisher.get_publisher_handle();
EXPECT_NE(nullptr, publisher_handle);
}
{
auto publisher = TestTSSetParameterResult(node.get());
std::shared_ptr<const rcl_publisher_t> publisher_handle = publisher.get_publisher_handle();
EXPECT_NE(nullptr, publisher_handle);
}
{
auto publisher = TestTSParameterDescriptor(node.get());
std::shared_ptr<const rcl_publisher_t> publisher_handle = publisher.get_publisher_handle();
EXPECT_NE(nullptr, publisher_handle);
}
{
auto publisher = TestTSListParametersResult(node.get());
std::shared_ptr<const rcl_publisher_t> publisher_handle = publisher.get_publisher_handle();
EXPECT_NE(nullptr, publisher_handle);
}
}
/* Testing type support getters */
TEST_F(TestTypeSupport, test_service_ts_get_params_srv) {
const rosidl_service_type_support_t * ts =
rclcpp::type_support::get_get_parameters_srv_type_support();
ASSERT_NE(nullptr, ts);
EXPECT_TRUE(test_type_support_init_fini(ts));
}
TEST_F(TestTypeSupport, test_service_ts_get_params_srv_type) {
const rosidl_service_type_support_t * ts =
rclcpp::type_support::get_get_parameters_srv_type_support();
ASSERT_NE(nullptr, ts);
EXPECT_TRUE(test_type_support_init_fini(ts));
}
TEST_F(TestTypeSupport, test_service_ts_get_parameters_types_srv) {
const rosidl_service_type_support_t * ts =
rclcpp::type_support::get_get_parameter_types_srv_type_support();
ASSERT_NE(nullptr, ts);
EXPECT_TRUE(test_type_support_init_fini(ts));
}
TEST_F(TestTypeSupport, test_service_ts_set_params_srv) {
const rosidl_service_type_support_t * ts =
rclcpp::type_support::get_set_parameters_srv_type_support();
ASSERT_NE(nullptr, ts);
EXPECT_TRUE(test_type_support_init_fini(ts));
}
TEST_F(TestTypeSupport, test_service_ts_list_params_srv) {
const rosidl_service_type_support_t * ts =
rclcpp::type_support::get_list_parameters_srv_type_support();
ASSERT_NE(nullptr, ts);
EXPECT_TRUE(test_type_support_init_fini(ts));
}
TEST_F(TestTypeSupport, test_service_ts_describe_params_srv) {
const rosidl_service_type_support_t * ts =
rclcpp::type_support::get_describe_parameters_srv_type_support();
ASSERT_NE(nullptr, ts);
EXPECT_TRUE(test_type_support_init_fini(ts));
}
TEST_F(TestTypeSupport, test_service_ts_set_params_atomically_srv) {
const rosidl_service_type_support_t * ts =
rclcpp::type_support::get_set_parameters_atomically_srv_type_support();
ASSERT_NE(nullptr, ts);
EXPECT_TRUE(test_type_support_init_fini(ts));
}