Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
47 changes: 47 additions & 0 deletions test_rmw_implementation/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
cmake_minimum_required(VERSION 3.5)

project(test_rmw_implementation)

# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

find_package(ament_cmake REQUIRED)

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(osrf_testing_tools_cpp REQUIRED)

find_package(rcutils REQUIRED)
find_package(rmw REQUIRED)
find_package(rmw_implementation REQUIRED)
find_package(rmw_implementation_cmake REQUIRED)

macro(test_api)
find_package(${rmw_implementation} REQUIRED)
message(STATUS "Creating API tests for '${rmw_implementation}'")
set(rmw_implementation_env_var RMW_IMPLEMENTATION=${rmw_implementation})

ament_add_gtest(test_init_shutdown${target_suffix}
test/test_init_shutdown.cpp
ENV ${rmw_implementation_env_var}
)
target_compile_definitions(test_init_shutdown${target_suffix}
PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}")
ament_target_dependencies(test_init_shutdown${target_suffix}
osrf_testing_tools_cpp rcutils rmw rmw_implementation
)
endmacro()

call_for_each_rmw_implementation(test_api)

find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_package()
23 changes: 23 additions & 0 deletions test_rmw_implementation/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>test_rmw_implementation</name>
<version>0.1.0</version>
<description>Test suite for ROS middleware API.</description>
<maintainer email="[email protected]">Michel Hidalgo</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>rmw_implementation_cmake</buildtool_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>osrf_testing_tools_cpp</test_depend>
<test_depend>rcutils</test_depend>
<test_depend>rmw</test_depend>
<test_depend>rmw_implementation</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
54 changes: 54 additions & 0 deletions test_rmw_implementation/test/test_init_shutdown.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
// Copyright 2020 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/scope_exit.hpp"

#include "rcutils/allocator.h"
#include "rcutils/error_handling.h"

#include "rmw/rmw.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 (TestInitShutdown, RMW_IMPLEMENTATION) : public ::testing::Test {};

TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), init_shutdown) {
rmw_context_t context = rmw_get_zero_initialized_context();
rmw_init_options_t options = rmw_get_zero_initialized_init_options();
rmw_ret_t ret = rmw_init_options_init(&options, rcutils_get_default_allocator());
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rmw_ret_t ret = rmw_init_options_fini(&options);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
});

ret = rmw_init(&options, &context);
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rmw_ret_t ret = rmw_context_fini(&context);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
});

ret = rmw_shutdown(&context);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
}