Skip to content

Commit ab75a16

Browse files
authored
Add init options API test coverage. (#108)
Signed-off-by: Michel Hidalgo <[email protected]>
1 parent 96ca972 commit ab75a16

File tree

3 files changed

+253
-0
lines changed

3 files changed

+253
-0
lines changed

test_rmw_implementation/CMakeLists.txt

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,16 @@ if(BUILD_TESTING)
3636
ament_target_dependencies(test_init_shutdown${target_suffix}
3737
osrf_testing_tools_cpp rcutils rmw rmw_implementation
3838
)
39+
40+
ament_add_gtest(test_init_options${target_suffix}
41+
test/test_init_options.cpp
42+
ENV ${rmw_implementation_env_var}
43+
)
44+
target_compile_definitions(test_init_options${target_suffix}
45+
PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}")
46+
ament_target_dependencies(test_init_options${target_suffix}
47+
osrf_testing_tools_cpp rcutils rmw rmw_implementation
48+
)
3949
endmacro()
4050

4151
call_for_each_rmw_implementation(test_api)
Lines changed: 94 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,94 @@
1+
// Copyright 2020 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef ALLOCATOR_TESTING_UTILS_H_
16+
#define ALLOCATOR_TESTING_UTILS_H_
17+
18+
#ifdef __cplusplus
19+
extern "C"
20+
{
21+
#endif
22+
23+
#include <stddef.h>
24+
25+
#include "rcutils/allocator.h"
26+
27+
typedef struct __failing_allocator_state
28+
{
29+
bool is_failing;
30+
} __failing_allocator_state;
31+
32+
void *
33+
failing_malloc(size_t size, void * state)
34+
{
35+
if (((__failing_allocator_state *)state)->is_failing) {
36+
return nullptr;
37+
}
38+
return rcutils_get_default_allocator().allocate(size, rcutils_get_default_allocator().state);
39+
}
40+
41+
void *
42+
failing_realloc(void * pointer, size_t size, void * state)
43+
{
44+
if (((__failing_allocator_state *)state)->is_failing) {
45+
return nullptr;
46+
}
47+
return rcutils_get_default_allocator().reallocate(
48+
pointer, size, rcutils_get_default_allocator().state);
49+
}
50+
51+
void
52+
failing_free(void * pointer, void * state)
53+
{
54+
if (((__failing_allocator_state *)state)->is_failing) {
55+
return;
56+
}
57+
rcutils_get_default_allocator().deallocate(pointer, rcutils_get_default_allocator().state);
58+
}
59+
60+
void *
61+
failing_calloc(size_t number_of_elements, size_t size_of_element, void * state)
62+
{
63+
if (((__failing_allocator_state *)state)->is_failing) {
64+
return nullptr;
65+
}
66+
return rcutils_get_default_allocator().zero_allocate(
67+
number_of_elements, size_of_element, rcutils_get_default_allocator().state);
68+
}
69+
70+
static inline rcutils_allocator_t
71+
get_failing_allocator(void)
72+
{
73+
static __failing_allocator_state state;
74+
state.is_failing = true;
75+
auto failing_allocator = rcutils_get_default_allocator();
76+
failing_allocator.allocate = failing_malloc;
77+
failing_allocator.deallocate = failing_free;
78+
failing_allocator.reallocate = failing_realloc;
79+
failing_allocator.zero_allocate = failing_calloc;
80+
failing_allocator.state = &state;
81+
return failing_allocator;
82+
}
83+
84+
static inline void
85+
set_failing_allocator_is_failing(rcutils_allocator_t & failing_allocator, bool state)
86+
{
87+
((__failing_allocator_state *)failing_allocator.state)->is_failing = state;
88+
}
89+
90+
#ifdef __cplusplus
91+
}
92+
#endif
93+
94+
#endif // ALLOCATOR_TESTING_UTILS_H_
Lines changed: 149 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,149 @@
1+
// Copyright 2020 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include <gtest/gtest.h>
16+
17+
#include "osrf_testing_tools_cpp/scope_exit.hpp"
18+
19+
#include "rcutils/allocator.h"
20+
#include "rcutils/error_handling.h"
21+
22+
#include "rmw/rmw.h"
23+
24+
#include "./allocator_testing_utils.h"
25+
26+
#ifdef RMW_IMPLEMENTATION
27+
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
28+
# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX)
29+
#else
30+
# define CLASSNAME(NAME, SUFFIX) NAME
31+
#endif
32+
33+
class CLASSNAME (TestInitOptions, RMW_IMPLEMENTATION) : public ::testing::Test {};
34+
35+
TEST_F(CLASSNAME(TestInitOptions, RMW_IMPLEMENTATION), init_copy_fini) {
36+
rmw_init_options_t src_options = rmw_get_zero_initialized_init_options();
37+
rmw_ret_t ret = rmw_init_options_init(&src_options, rcutils_get_default_allocator());
38+
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
39+
40+
// Initializing twice fails.
41+
ret = rmw_init_options_init(&src_options, rcutils_get_default_allocator());
42+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
43+
rcutils_reset_error();
44+
45+
rmw_init_options_t dst_options = rmw_get_zero_initialized_init_options();
46+
ret = rmw_init_options_copy(&src_options, &dst_options);
47+
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
48+
49+
// Copying twice fails.
50+
ret = rmw_init_options_copy(&src_options, &dst_options);
51+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret) << rcutils_get_error_string().str;
52+
rcutils_reset_error();
53+
54+
ret = rmw_init_options_fini(&dst_options);
55+
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
56+
57+
ret = rmw_init_options_fini(&src_options);
58+
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
59+
60+
// Finalizing twice fails.
61+
ret = rmw_init_options_fini(&src_options);
62+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
63+
rcutils_reset_error();
64+
}
65+
66+
TEST_F(CLASSNAME(TestInitOptions, RMW_IMPLEMENTATION), init_with_bad_arguments) {
67+
rmw_init_options_t options = rmw_get_zero_initialized_init_options();
68+
rmw_ret_t ret = rmw_init_options_init(&options, rcutils_get_zero_initialized_allocator());
69+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
70+
rcutils_reset_error();
71+
72+
ret = rmw_init_options_init(nullptr, rcutils_get_default_allocator());
73+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
74+
rcutils_reset_error();
75+
76+
// Initialization and finalization should still succeed.
77+
ret = rmw_init_options_init(&options, rcutils_get_default_allocator());
78+
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
79+
ret = rmw_init_options_fini(&options);
80+
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
81+
}
82+
83+
TEST_F(CLASSNAME(TestInitOptions, RMW_IMPLEMENTATION), copy_with_bad_arguments) {
84+
rmw_init_options_t src_options = rmw_get_zero_initialized_init_options();
85+
rmw_init_options_t dst_options = rmw_get_zero_initialized_init_options();
86+
87+
rmw_ret_t ret = rmw_init_options_copy(nullptr, &dst_options);
88+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
89+
rcutils_reset_error();
90+
91+
ret = rmw_init_options_copy(&src_options, nullptr);
92+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
93+
rcutils_reset_error();
94+
95+
ret = rmw_init_options_copy(&src_options, &dst_options);
96+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
97+
rcutils_reset_error();
98+
99+
ret = rmw_init_options_init(&src_options, rcutils_get_default_allocator());
100+
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
101+
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
102+
{
103+
rmw_ret_t ret = rmw_init_options_fini(&src_options);
104+
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
105+
});
106+
107+
const char * implementation_identifier = src_options.implementation_identifier;
108+
src_options.implementation_identifier = "not-an-rmw-implementation-identifier";
109+
ret = rmw_init_options_copy(&src_options, &dst_options);
110+
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ret);
111+
src_options.implementation_identifier = implementation_identifier;
112+
rcutils_reset_error();
113+
114+
// Initialization and finalization should still succeed.
115+
ret = rmw_init_options_init(&dst_options, rcutils_get_default_allocator());
116+
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
117+
ret = rmw_init_options_fini(&dst_options);
118+
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
119+
}
120+
121+
TEST_F(CLASSNAME(TestInitOptions, RMW_IMPLEMENTATION), fini_with_bad_arguments) {
122+
rmw_init_options_t options = rmw_get_zero_initialized_init_options();
123+
rmw_ret_t ret = rmw_init_options_fini(&options);
124+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
125+
rcutils_reset_error();
126+
127+
ret = rmw_init_options_fini(nullptr);
128+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
129+
rcutils_reset_error();
130+
131+
ret = rmw_init_options_init(&options, rcutils_get_default_allocator());
132+
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
133+
134+
const char * implementation_identifier = options.implementation_identifier;
135+
options.implementation_identifier = "not-an-rmw-implementation-identifier";
136+
ret = rmw_init_options_fini(&options);
137+
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ret);
138+
options.implementation_identifier = implementation_identifier;
139+
rcutils_reset_error();
140+
141+
ret = rmw_init_options_fini(&options);
142+
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
143+
144+
// Initialization and finalization should still succeed.
145+
ret = rmw_init_options_init(&options, rcutils_get_default_allocator());
146+
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
147+
ret = rmw_init_options_fini(&options);
148+
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
149+
}

0 commit comments

Comments
 (0)