-
Notifications
You must be signed in to change notification settings - Fork 527
Expand file tree
/
Copy pathtest_client.cpp
More file actions
101 lines (88 loc) · 2.51 KB
/
test_client.cpp
File metadata and controls
101 lines (88 loc) · 2.51 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
// Copyright 2022 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 <utility>
#include "rclcpp/exceptions.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rcl_interfaces/srv/list_parameters.hpp"
#include "rmw/qos_profiles.h"
class TestClient : public ::testing::Test
{
protected:
static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}
static void TearDownTestCase()
{
rclcpp::shutdown();
}
void SetUp()
{
node_ = std::make_shared<rclcpp_lifecycle::LifecycleNode>("my_lifecycle_node", "/ns");
}
void TearDown()
{
node_.reset();
}
rclcpp_lifecycle::LifecycleNode::SharedPtr node_;
};
/*
Testing client construction and destruction.
*/
TEST_F(TestClient, construction_and_destruction) {
using rcl_interfaces::srv::ListParameters;
{
auto client = node_->create_client<ListParameters>("service");
EXPECT_TRUE(client);
}
{
auto client = node_->create_client<ListParameters>(
"service", rclcpp::ServicesQoS());
EXPECT_TRUE(client);
}
{
ASSERT_THROW(
{
auto client = node_->create_client<ListParameters>("invalid_service?");
}, rclcpp::exceptions::InvalidServiceNameError);
}
}
TEST_F(TestClient, construction_with_free_function) {
{
auto client = rclcpp::create_client<rcl_interfaces::srv::ListParameters>(
node_->get_node_base_interface(),
node_->get_node_graph_interface(),
node_->get_node_services_interface(),
"service",
rclcpp::ServicesQoS(),
nullptr);
EXPECT_TRUE(client);
}
{
ASSERT_THROW(
{
auto client = rclcpp::create_client<rcl_interfaces::srv::ListParameters>(
node_->get_node_base_interface(),
node_->get_node_graph_interface(),
node_->get_node_services_interface(),
"invalid_?service",
rclcpp::ServicesQoS(),
nullptr);
}, rclcpp::exceptions::InvalidServiceNameError);
}
}