forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathtest_parameter_client.cpp
More file actions
161 lines (139 loc) · 4.35 KB
/
test_parameter_client.cpp
File metadata and controls
161 lines (139 loc) · 4.35 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
// Copyright 2019 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 <string>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "rcl_interfaces/msg/parameter_event.hpp"
class TestParameterClient : public ::testing::Test
{
public:
void OnMessage(const rcl_interfaces::msg::ParameterEvent::SharedPtr event)
{
(void)event;
}
protected:
static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}
void SetUp()
{
node = std::make_shared<rclcpp::Node>("test_parameter_client", "/ns");
}
void TearDown()
{
node.reset();
}
rclcpp::Node::SharedPtr node;
};
/*
Testing async parameter client construction and destruction.
*/
TEST_F(TestParameterClient, async_construction_and_destruction) {
{
auto asynchronous_client = std::make_shared<rclcpp::AsyncParametersClient>(node);
(void)asynchronous_client;
}
{
auto asynchronous_client = std::make_shared<rclcpp::AsyncParametersClient>(
node->get_node_base_interface(),
node->get_node_topics_interface(),
node->get_node_graph_interface(),
node->get_node_services_interface());
(void)asynchronous_client;
}
{
ASSERT_THROW(
{
auto asynchronous_client = std::make_shared<rclcpp::AsyncParametersClient>(
node, "invalid_remote_node?");
(void)asynchronous_client;
}, rclcpp::exceptions::InvalidServiceNameError);
}
}
/*
Testing sync parameter client construction and destruction.
*/
TEST_F(TestParameterClient, sync_construction_and_destruction) {
{
auto synchronous_client = std::make_shared<rclcpp::SyncParametersClient>(node);
(void)synchronous_client;
}
{
auto synchronous_client = std::make_shared<rclcpp::SyncParametersClient>(
std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
node);
(void)synchronous_client;
}
{
auto synchronous_client = std::make_shared<rclcpp::SyncParametersClient>(
std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
node->get_node_base_interface(),
node->get_node_topics_interface(),
node->get_node_graph_interface(),
node->get_node_services_interface());
(void)synchronous_client;
}
{
ASSERT_THROW(
{
auto synchronous_client = std::make_shared<rclcpp::SyncParametersClient>(
node, "invalid_remote_node?");
(void)synchronous_client;
}, rclcpp::exceptions::InvalidServiceNameError);
}
}
/*
Testing different methods for parameter event subscription from asynchronous clients.
*/
TEST_F(TestParameterClient, async_parameter_event_subscription) {
auto callback = std::bind(&TestParameterClient::OnMessage, this, std::placeholders::_1);
{
auto asynchronous_client = std::make_shared<rclcpp::AsyncParametersClient>(node);
auto event_sub = asynchronous_client->on_parameter_event(callback);
(void)event_sub;
}
{
auto event_sub = rclcpp::AsyncParametersClient::on_parameter_event(node, callback);
(void)event_sub;
}
{
auto event_sub = rclcpp::AsyncParametersClient::on_parameter_event(
node->get_node_topics_interface(),
callback);
(void)event_sub;
}
}
/*
Testing different methods for parameter event subscription from synchronous clients.
*/
TEST_F(TestParameterClient, sync_parameter_event_subscription) {
auto callback = std::bind(&TestParameterClient::OnMessage, this, std::placeholders::_1);
{
auto synchronous_client = std::make_shared<rclcpp::SyncParametersClient>(node);
auto event_sub = synchronous_client->on_parameter_event(callback);
(void)event_sub;
}
{
auto event_sub = rclcpp::SyncParametersClient::on_parameter_event(node, callback);
(void)event_sub;
}
{
auto event_sub = rclcpp::SyncParametersClient::on_parameter_event(
node->get_node_topics_interface(),
callback);
(void)event_sub;
}
}