Skip to content

Commit

Permalink
add method for accessing rmw_context from rcl_context (#372)
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood authored Jan 10, 2019
1 parent ecc3cb5 commit c60290e
Show file tree
Hide file tree
Showing 4 changed files with 152 additions and 0 deletions.
22 changes: 22 additions & 0 deletions rcl/include/rcl/context.h
Original file line number Diff line number Diff line change
Expand Up @@ -261,6 +261,28 @@ RCL_WARN_UNUSED
bool
rcl_context_is_valid(rcl_context_t * context);

/// Return pointer to the rmw context if the given context is currently valid, otherwise `NULL`.
/**
* If context is `NULL`, then `NULL` is returned.
* If context is zero-initialized, then `NULL` is returned.
* If context is uninitialized, then it is undefined behavior.
*
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | Yes
* Uses Atomics | Yes
* Lock-Free | Yes [1]
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t`</i>
*
* \param[in] context object from which the rmw context should be retrieved.
* \return pointer to rmw context if valid, otherwise `NULL`
*/
RCL_PUBLIC
RCL_WARN_UNUSED
rmw_context_t *
rcl_context_get_rmw_context(rcl_context_t * context);

#ifdef __cplusplus
}
#endif
Expand Down
8 changes: 8 additions & 0 deletions rcl/src/rcl/context.c
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,14 @@ rcl_context_is_valid(rcl_context_t * context)
return 0 != rcl_context_get_instance_id(context);
}

rmw_context_t *
rcl_context_get_rmw_context(rcl_context_t * context)
{
RCL_CHECK_ARGUMENT_FOR_NULL(context, NULL);
RCL_CHECK_FOR_NULL_WITH_MSG(context->impl, "context is zero-initialized", return NULL);
return &(context->impl->rmw_context);
}

void
__cleanup_context(rcl_context_t * context)
{
Expand Down
8 changes: 8 additions & 0 deletions rcl/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,14 @@ function(test_target_function)
AMENT_DEPENDENCIES ${rmw_implementation}
)

rcl_add_custom_gtest(test_context${target_suffix}
SRCS rcl/test_context.cpp
ENV ${rmw_implementation_env_var} ${memory_tools_ld_preload_env_var}
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools
AMENT_DEPENDENCIES ${rmw_implementation}
)

rcl_add_custom_gtest(test_get_node_names${target_suffix}
SRCS rcl/test_get_node_names.cpp
INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS}
Expand Down
114 changes: 114 additions & 0 deletions rcl/test/rcl/test_context.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,114 @@
// 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 "osrf_testing_tools_cpp/memory_tools/gtest_quickstart.hpp"
#include "osrf_testing_tools_cpp/scope_exit.hpp"
#include "rcl/context.h"
#include "rcl/error_handling.h"
#include "rcl/init.h"

#ifdef RMW_IMPLEMENTATION
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX)
#else
# define CLASSNAME(NAME, SUFFIX) NAME
#endif

class CLASSNAME (TestContextFixture, RMW_IMPLEMENTATION) : public ::testing::Test {};

// Test the rcl_context_t's normal function.
// Note: that init/fini are tested in test_init.cpp.
TEST_F(CLASSNAME(TestContextFixture, RMW_IMPLEMENTATION), nominal) {
osrf_testing_tools_cpp::memory_tools::ScopedQuickstartGtest scoped_quickstart_gtest;

// This prevents memory allocations when setting error states in the future.
rcl_ret_t ret = rcl_initialize_error_handling_thread_local_storage(rcl_get_default_allocator());
ASSERT_EQ(ret, RCL_RET_OK);

// initialization with rcl_init
rcl_context_t context = rcl_get_zero_initialized_context();
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
ret = rcl_init_options_init(&init_options, rcl_get_default_allocator());
ASSERT_EQ(ret, RCL_RET_OK);
ret = rcl_init(0, nullptr, &init_options, &context);
ASSERT_EQ(ret, RCL_RET_OK);
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
ret = rcl_shutdown(&context);
EXPECT_EQ(ret, RCL_RET_OK);
ret = rcl_context_fini(&context);
EXPECT_EQ(ret, RCL_RET_OK);
});

// test rcl_context_get_init_options
const rcl_init_options_t * init_options_ptr;
EXPECT_NO_MEMORY_OPERATIONS({
init_options_ptr = rcl_context_get_init_options(nullptr);
});
EXPECT_EQ(init_options_ptr, nullptr);
EXPECT_TRUE(rcl_error_is_set());
rcl_reset_error();

EXPECT_NO_MEMORY_OPERATIONS({
init_options_ptr = rcl_context_get_init_options(&context);
});
EXPECT_NE(init_options_ptr, nullptr) << rcl_get_error_string().str;
rcl_reset_error();

// test rcl_context_get_instance_id
rcl_context_instance_id_t instance_id;
EXPECT_NO_MEMORY_OPERATIONS({
instance_id = rcl_context_get_instance_id(nullptr);
});
EXPECT_EQ(instance_id, 0UL);
EXPECT_TRUE(rcl_error_is_set());
rcl_reset_error();

EXPECT_NO_MEMORY_OPERATIONS({
instance_id = rcl_context_get_instance_id(&context);
});
EXPECT_NE(instance_id, 0UL) << rcl_get_error_string().str;
rcl_reset_error();

// test rcl_context_is_valid
bool is_valid;
EXPECT_NO_MEMORY_OPERATIONS({
is_valid = rcl_context_is_valid(nullptr);
});
EXPECT_FALSE(is_valid);
EXPECT_TRUE(rcl_error_is_set());
rcl_reset_error();

EXPECT_NO_MEMORY_OPERATIONS({
is_valid = rcl_context_is_valid(&context);
});
EXPECT_TRUE(is_valid) << rcl_get_error_string().str;
rcl_reset_error();

// test rcl_context_get_rmw_context
rmw_context_t * rmw_context_ptr;
EXPECT_NO_MEMORY_OPERATIONS({
rmw_context_ptr = rcl_context_get_rmw_context(nullptr);
});
EXPECT_EQ(rmw_context_ptr, nullptr);
EXPECT_TRUE(rcl_error_is_set());
rcl_reset_error();

EXPECT_NO_MEMORY_OPERATIONS({
rmw_context_ptr = rcl_context_get_rmw_context(&context);
});
EXPECT_NE(rmw_context_ptr, nullptr) << rcl_get_error_string().str;
rcl_reset_error();
}

0 comments on commit c60290e

Please sign in to comment.