[rcl action] Adds action client tests.
This commit is contained in:
parent
cca18daad2
commit
7efd1a15ae
4 changed files with 235 additions and 15 deletions
|
@ -70,20 +70,23 @@ install(TARGETS ${PROJECT_NAME}
|
||||||
if(BUILD_TESTING)
|
if(BUILD_TESTING)
|
||||||
find_package(ament_cmake_gtest REQUIRED)
|
find_package(ament_cmake_gtest REQUIRED)
|
||||||
find_package(ament_lint_auto REQUIRED)
|
find_package(ament_lint_auto REQUIRED)
|
||||||
|
find_package(test_msgs REQUIRED)
|
||||||
ament_lint_auto_find_test_dependencies()
|
ament_lint_auto_find_test_dependencies()
|
||||||
ament_find_gtest()
|
ament_find_gtest()
|
||||||
# Gtests
|
# Gtests
|
||||||
# ament_add_gtest(test_action_client
|
ament_add_gtest(test_action_client
|
||||||
# test/rcl_action/test_action_client.cpp
|
test/rcl_action/test_action_client.cpp
|
||||||
# )
|
)
|
||||||
# if(TARGET test_action_client)
|
if(TARGET test_action_client)
|
||||||
# target_include_directories(test_action_client PUBLIC
|
target_include_directories(test_action_client PUBLIC
|
||||||
# ${rcl_INCLUDE_DIRS}
|
${rcl_INCLUDE_DIRS}
|
||||||
# )
|
${test_msgs_INCLUDE_DIRS}
|
||||||
# target_link_libraries(test_action_client
|
)
|
||||||
# ${PROJECT_NAME}
|
target_link_libraries(test_action_client
|
||||||
# )
|
${PROJECT_NAME}
|
||||||
# endif()
|
${test_msgs_LIBRARIES}
|
||||||
|
)
|
||||||
|
endif()
|
||||||
ament_add_gtest(test_goal_handle
|
ament_add_gtest(test_goal_handle
|
||||||
test/rcl_action/test_goal_handle.cpp
|
test/rcl_action/test_goal_handle.cpp
|
||||||
)
|
)
|
||||||
|
|
|
@ -18,6 +18,7 @@
|
||||||
<test_depend>ament_cmake_gtest</test_depend>
|
<test_depend>ament_cmake_gtest</test_depend>
|
||||||
<test_depend>ament_lint_common</test_depend>
|
<test_depend>ament_lint_common</test_depend>
|
||||||
<test_depend>ament_lint_auto</test_depend>
|
<test_depend>ament_lint_auto</test_depend>
|
||||||
|
<test_depend>test_msgs</test_depend>
|
||||||
|
|
||||||
<export>
|
<export>
|
||||||
<build_type>ament_cmake</build_type>
|
<build_type>ament_cmake</build_type>
|
||||||
|
|
|
@ -18,6 +18,7 @@ extern "C"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "rcl_action/action_client.h"
|
#include "rcl_action/action_client.h"
|
||||||
|
|
||||||
#include "rcl_action/default_qos.h"
|
#include "rcl_action/default_qos.h"
|
||||||
#include "rcl_action/names.h"
|
#include "rcl_action/names.h"
|
||||||
#include "rcl_action/types.h"
|
#include "rcl_action/types.h"
|
||||||
|
@ -322,7 +323,7 @@ rcl_action_client_init(
|
||||||
return RCL_RET_ALREADY_INIT;
|
return RCL_RET_ALREADY_INIT;
|
||||||
}
|
}
|
||||||
// Allocate space for the implementation struct.
|
// Allocate space for the implementation struct.
|
||||||
rcl_action_client_impl_t *impl = action_client->impl = allocator->allocate(
|
rcl_action_client_impl_t * impl = action_client->impl = allocator->allocate(
|
||||||
sizeof(rcl_action_client_impl_t), allocator->state);
|
sizeof(rcl_action_client_impl_t), allocator->state);
|
||||||
RCL_CHECK_FOR_NULL_WITH_MSG(impl, "allocating memory failed", return RCL_RET_BAD_ALLOC);
|
RCL_CHECK_FOR_NULL_WITH_MSG(impl, "allocating memory failed", return RCL_RET_BAD_ALLOC);
|
||||||
// Copy action client name and options.
|
// Copy action client name and options.
|
||||||
|
@ -688,7 +689,8 @@ rcl_action_client_get_action_name(const rcl_action_client_t * action_client)
|
||||||
}
|
}
|
||||||
|
|
||||||
const rcl_action_client_options_t *
|
const rcl_action_client_options_t *
|
||||||
rcl_action_client_get_options(const rcl_action_client_t * action_client) {
|
rcl_action_client_get_options(const rcl_action_client_t * action_client)
|
||||||
|
{
|
||||||
if (!rcl_action_client_is_valid(action_client)) {
|
if (!rcl_action_client_is_valid(action_client)) {
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
@ -699,7 +701,7 @@ bool
|
||||||
rcl_action_client_is_valid(const rcl_action_client_t * action_client)
|
rcl_action_client_is_valid(const rcl_action_client_t * action_client)
|
||||||
{
|
{
|
||||||
RCL_CHECK_FOR_NULL_WITH_MSG(
|
RCL_CHECK_FOR_NULL_WITH_MSG(
|
||||||
action_client,"action client pointer is invalid", return false);
|
action_client, "action client pointer is invalid", return false);
|
||||||
RCL_CHECK_FOR_NULL_WITH_MSG(
|
RCL_CHECK_FOR_NULL_WITH_MSG(
|
||||||
action_client->impl, "action client implementation is invalid", return false);
|
action_client->impl, "action client implementation is invalid", return false);
|
||||||
return true;
|
return true;
|
||||||
|
@ -708,7 +710,8 @@ rcl_action_client_is_valid(const rcl_action_client_t * action_client)
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_action_wait_set_add_action_client(
|
rcl_action_wait_set_add_action_client(
|
||||||
rcl_wait_set_t * wait_set,
|
rcl_wait_set_t * wait_set,
|
||||||
const rcl_action_client_t * action_client) {
|
const rcl_action_client_t * action_client)
|
||||||
|
{
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_WAIT_SET_INVALID);
|
RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_WAIT_SET_INVALID);
|
||||||
if (!rcl_action_client_is_valid(action_client)) {
|
if (!rcl_action_client_is_valid(action_client)) {
|
||||||
|
|
213
rcl_action/test/rcl_action/test_action_client.cpp
Normal file
213
rcl_action/test/rcl_action/test_action_client.cpp
Normal file
|
@ -0,0 +1,213 @@
|
||||||
|
// Copyright 2018 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 "rcl_action/action_client.h"
|
||||||
|
|
||||||
|
#include "rcl/error_handling.h"
|
||||||
|
#include "rcl/rcl.h"
|
||||||
|
|
||||||
|
#include "test_msgs/action/fibonacci.h"
|
||||||
|
|
||||||
|
class TestActionClientBaseFixture : public ::testing::Test
|
||||||
|
{
|
||||||
|
protected:
|
||||||
|
void SetUp() override
|
||||||
|
{
|
||||||
|
rcl_ret_t ret = rcl_init(0, nullptr, rcl_get_default_allocator());
|
||||||
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
this->node = rcl_get_zero_initialized_node();
|
||||||
|
rcl_node_options_t node_options = rcl_node_get_default_options();
|
||||||
|
const char * node_name = "test_action_client_node";
|
||||||
|
ret = rcl_node_init(&this->node, node_name, "", &node_options);
|
||||||
|
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
}
|
||||||
|
|
||||||
|
void TearDown() override
|
||||||
|
{
|
||||||
|
rcl_ret_t ret = rcl_node_fini(&this->node);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
ret = rcl_shutdown();
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
}
|
||||||
|
|
||||||
|
rcl_node_t node;
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
TEST_F(TestActionClientBaseFixture, test_action_client_init_fini) {
|
||||||
|
rcl_ret_t ret = RCL_RET_OK;
|
||||||
|
rcl_action_client_t invalid_action_client =
|
||||||
|
rcl_action_get_zero_initialized_client();
|
||||||
|
rcl_node_t invalid_node = rcl_get_zero_initialized_node();
|
||||||
|
const char * action_name = "test_action_client_name";
|
||||||
|
const rosidl_action_type_support_t * action_typesupport =
|
||||||
|
ROSIDL_GET_ACTION_TYPE_SUPPORT(test_msgs, Fibonacci);
|
||||||
|
const rcl_action_client_options_t action_client_options =
|
||||||
|
rcl_action_client_get_default_options();
|
||||||
|
rcl_action_client_options_t invalid_action_client_options =
|
||||||
|
rcl_action_client_get_default_options();
|
||||||
|
invalid_action_client_options.allocator =
|
||||||
|
(rcl_allocator_t)rcutils_get_zero_initialized_allocator();
|
||||||
|
rcl_action_client_t action_client = rcl_action_get_zero_initialized_client();
|
||||||
|
|
||||||
|
ret = rcl_action_client_init(
|
||||||
|
nullptr, &this->node, action_typesupport,
|
||||||
|
action_name, &action_client_options);
|
||||||
|
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
ret = rcl_action_client_init(
|
||||||
|
&action_client, nullptr, action_typesupport,
|
||||||
|
action_name, &action_client_options);
|
||||||
|
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
ret = rcl_action_client_init(
|
||||||
|
&action_client, &invalid_node, action_typesupport,
|
||||||
|
action_name, &action_client_options);
|
||||||
|
EXPECT_EQ(ret, RCL_RET_NODE_INVALID) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
ret = rcl_action_client_init(
|
||||||
|
&action_client, &this->node, nullptr,
|
||||||
|
action_name, &action_client_options);
|
||||||
|
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
ret = rcl_action_client_init(
|
||||||
|
&action_client, &this->node, action_typesupport,
|
||||||
|
nullptr, &action_client_options);
|
||||||
|
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
ret = rcl_action_client_init(
|
||||||
|
&action_client, &this->node,
|
||||||
|
action_typesupport, action_name,
|
||||||
|
nullptr);
|
||||||
|
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
ret = rcl_action_client_init(
|
||||||
|
&action_client, &this->node,
|
||||||
|
action_typesupport, action_name,
|
||||||
|
&invalid_action_client_options);
|
||||||
|
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
ret = rcl_action_client_init(
|
||||||
|
&action_client, &this->node, action_typesupport,
|
||||||
|
action_name, &action_client_options);
|
||||||
|
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
ret = rcl_action_client_init(
|
||||||
|
&action_client, &this->node, action_typesupport,
|
||||||
|
action_name, &action_client_options);
|
||||||
|
EXPECT_EQ(ret, RCL_RET_ALREADY_INIT) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
ret = rcl_action_client_fini(nullptr, &this->node);
|
||||||
|
EXPECT_EQ(ret, RCL_RET_ACTION_CLIENT_INVALID) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
ret = rcl_action_client_fini(&invalid_action_client, &this->node);
|
||||||
|
EXPECT_EQ(ret, RCL_RET_ACTION_CLIENT_INVALID) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
ret = rcl_action_client_fini(&action_client, nullptr);
|
||||||
|
EXPECT_EQ(ret, RCL_RET_NODE_INVALID) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
ret = rcl_action_client_fini(&action_client, &invalid_node);
|
||||||
|
EXPECT_EQ(ret, RCL_RET_NODE_INVALID) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
ret = rcl_action_client_fini(&action_client, &this->node);
|
||||||
|
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
}
|
||||||
|
|
||||||
|
class TestActionClientFixture : public TestActionClientBaseFixture
|
||||||
|
{
|
||||||
|
protected:
|
||||||
|
void SetUp() override
|
||||||
|
{
|
||||||
|
TestActionClientBaseFixture::SetUp();
|
||||||
|
this->action_client = rcl_action_get_zero_initialized_client();
|
||||||
|
const rosidl_action_type_support_t * action_typesupport =
|
||||||
|
ROSIDL_GET_ACTION_TYPE_SUPPORT(test_msgs, Fibonacci);
|
||||||
|
this->action_client_options = rcl_action_client_get_default_options();
|
||||||
|
rcl_ret_t ret = rcl_action_client_init(
|
||||||
|
&this->action_client, &this->node, action_typesupport,
|
||||||
|
this->action_name, &this->action_client_options);
|
||||||
|
ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
|
||||||
|
this->invalid_action_client = rcl_action_get_zero_initialized_client();
|
||||||
|
}
|
||||||
|
|
||||||
|
void TearDown() override
|
||||||
|
{
|
||||||
|
rcl_ret_t ret = rcl_action_client_fini(&this->action_client, &this->node);
|
||||||
|
ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
|
||||||
|
TestActionClientBaseFixture::TearDown();
|
||||||
|
}
|
||||||
|
|
||||||
|
const char * const action_name = "test_action_client_name";
|
||||||
|
rcl_action_client_options_t action_client_options;
|
||||||
|
rcl_action_client_t invalid_action_client;
|
||||||
|
rcl_action_client_t action_client;
|
||||||
|
};
|
||||||
|
|
||||||
|
TEST_F(TestActionClientFixture, test_action_client_is_valid) {
|
||||||
|
bool is_valid = rcl_action_client_is_valid(nullptr);
|
||||||
|
EXPECT_FALSE(is_valid) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
is_valid = rcl_action_client_is_valid(&this->invalid_action_client);
|
||||||
|
EXPECT_FALSE(is_valid) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
is_valid = rcl_action_client_is_valid(&this->action_client);
|
||||||
|
EXPECT_TRUE(is_valid) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(TestActionClientFixture, test_action_client_get_action_name) {
|
||||||
|
const char * name = rcl_action_client_get_action_name(nullptr);
|
||||||
|
EXPECT_EQ(name, nullptr) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
name = rcl_action_client_get_action_name(&this->invalid_action_client);
|
||||||
|
EXPECT_EQ(name, nullptr) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
name = rcl_action_client_get_action_name(&this->action_client);
|
||||||
|
ASSERT_NE(name, nullptr) << rcl_get_error_string().str;
|
||||||
|
EXPECT_STREQ(name, this->action_name);
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(TestActionClientFixture, test_action_client_get_options) {
|
||||||
|
const rcl_action_client_options_t * options =
|
||||||
|
rcl_action_client_get_options(nullptr);
|
||||||
|
EXPECT_EQ(options, nullptr) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
options = rcl_action_client_get_options(&this->invalid_action_client);
|
||||||
|
EXPECT_EQ(options, nullptr) << rcl_get_error_string().str;
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
options = rcl_action_client_get_options(&this->action_client);
|
||||||
|
ASSERT_NE(options, nullptr) << rcl_get_error_string().str;
|
||||||
|
}
|
Loading…
Add table
Add a link
Reference in a new issue