forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathtest_utilities.cpp
More file actions
83 lines (64 loc) · 2.57 KB
/
test_utilities.cpp
File metadata and controls
83 lines (64 loc) · 2.57 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
// Copyright 2017 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/contexts/default_context.hpp"
#include "rclcpp/exceptions.hpp"
#include "rclcpp/utilities.hpp"
TEST(TestUtilities, remove_ros_arguments) {
const char * const argv[] = {"process_name", "-d", "__ns:=/foo/bar",
"__ns:=/fiz/buz", "--foo=bar", "--baz"};
int argc = sizeof(argv) / sizeof(const char *);
auto args = rclcpp::remove_ros_arguments(argc, argv);
ASSERT_EQ(4u, args.size());
ASSERT_EQ(std::string{"process_name"}, args[0]);
ASSERT_EQ(std::string{"-d"}, args[1]);
ASSERT_EQ(std::string{"--foo=bar"}, args[2]);
ASSERT_EQ(std::string{"--baz"}, args[3]);
}
TEST(TestUtilities, remove_ros_arguments_null) {
// In the case of a C executable, we would expect to get
// argc=1 and argv = ["process_name"], so this is an invalid input.
ASSERT_THROW({
rclcpp::remove_ros_arguments(0, nullptr);
}, rclcpp::exceptions::RCLErrorBase);
}
TEST(TestUtilities, init_with_args) {
const char * const argv[] = {"process_name"};
int argc = sizeof(argv) / sizeof(const char *);
auto other_args = rclcpp::init_and_remove_ros_arguments(argc, argv);
ASSERT_EQ(1u, other_args.size());
ASSERT_EQ(std::string{"process_name"}, other_args[0]);
EXPECT_TRUE(rclcpp::ok());
rclcpp::shutdown();
}
TEST(TestUtilities, multi_init) {
auto context1 = std::make_shared<rclcpp::contexts::default_context::DefaultContext>();
auto context2 = std::make_shared<rclcpp::contexts::default_context::DefaultContext>();
EXPECT_FALSE(rclcpp::ok(context1));
EXPECT_FALSE(rclcpp::ok(context2));
context1->init(0, nullptr);
EXPECT_TRUE(rclcpp::ok(context1));
EXPECT_FALSE(rclcpp::ok(context2));
context2->init(0, nullptr);
EXPECT_TRUE(rclcpp::ok(context1));
EXPECT_TRUE(rclcpp::ok(context2));
rclcpp::shutdown(context1);
EXPECT_FALSE(rclcpp::ok(context1));
EXPECT_TRUE(rclcpp::ok(context2));
rclcpp::shutdown(context2);
EXPECT_FALSE(rclcpp::ok(context1));
EXPECT_FALSE(rclcpp::ok(context2));
}