Increase coverage rclcpp_action to 95% (#1290)
* Increase coverage rclcpp_action to 95% Signed-off-by: Stephen Brawner <brawner@gmail.com> * PR fixup Signed-off-by: Stephen Brawner <brawner@gmail.com> * Address PR Feedback Signed-off-by: Stephen Brawner <brawner@gmail.com> * Rebase onto #1311 Signed-off-by: Stephen Brawner <brawner@gmail.com> * rcutils test depend Signed-off-by: Stephen Brawner <brawner@gmail.com> * Cleaning up Signed-off-by: Stephen Brawner <brawner@gmail.com>
This commit is contained in:
parent
43df9eff37
commit
730e99b742
6 changed files with 1062 additions and 23 deletions
|
@ -77,20 +77,36 @@ if(BUILD_TESTING)
|
|||
ament_add_gtest(test_client test/test_client.cpp TIMEOUT 120)
|
||||
if(TARGET test_client)
|
||||
ament_target_dependencies(test_client
|
||||
"rcutils"
|
||||
"test_msgs"
|
||||
)
|
||||
target_link_libraries(test_client
|
||||
${PROJECT_NAME}
|
||||
mimick
|
||||
)
|
||||
endif()
|
||||
|
||||
ament_add_gtest(test_server test/test_server.cpp)
|
||||
if(TARGET test_server)
|
||||
ament_target_dependencies(test_server
|
||||
"rcutils"
|
||||
"test_msgs"
|
||||
)
|
||||
target_link_libraries(test_server
|
||||
${PROJECT_NAME}
|
||||
mimick
|
||||
)
|
||||
endif()
|
||||
|
||||
ament_add_gtest(test_server_goal_handle test/test_server_goal_handle.cpp)
|
||||
if(TARGET test_server_goal_handle)
|
||||
ament_target_dependencies(test_server_goal_handle
|
||||
"rcutils"
|
||||
"test_msgs"
|
||||
)
|
||||
target_link_libraries(test_server_goal_handle
|
||||
${PROJECT_NAME}
|
||||
mimick
|
||||
)
|
||||
endif()
|
||||
|
||||
|
|
|
@ -22,6 +22,7 @@
|
|||
<test_depend>ament_cmake_gtest</test_depend>
|
||||
<test_depend>ament_lint_auto</test_depend>
|
||||
<test_depend>ament_lint_common</test_depend>
|
||||
<test_depend>mimick_vendor</test_depend>
|
||||
<test_depend>test_msgs</test_depend>
|
||||
|
||||
<export>
|
||||
|
|
393
rclcpp_action/test/mocking_utils/patch.hpp
Normal file
393
rclcpp_action/test/mocking_utils/patch.hpp
Normal file
|
@ -0,0 +1,393 @@
|
|||
// 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.
|
||||
|
||||
// Original file taken from:
|
||||
// https://github.com/ros2/rcutils/blob/master/test/mocking_utils/patch.hpp
|
||||
|
||||
#ifndef MOCKING_UTILS__PATCH_HPP_
|
||||
#define MOCKING_UTILS__PATCH_HPP_
|
||||
|
||||
#define MOCKING_UTILS_SUPPORT_VA_LIST
|
||||
#if (defined(__aarch64__) || defined(__arm__) || defined(_M_ARM) || defined(__thumb__))
|
||||
// In ARM machines, va_list does not define comparison operators
|
||||
// nor the compiler allows defining them via operator overloads.
|
||||
// Thus, Mimick argument matching code will not compile.
|
||||
#undef MOCKING_UTILS_SUPPORT_VA_LIST
|
||||
#endif
|
||||
|
||||
#ifdef MOCKING_UTILS_SUPPORT_VA_LIST
|
||||
#include <cstdarg>
|
||||
#endif
|
||||
|
||||
#include <functional>
|
||||
#include <string>
|
||||
#include <type_traits>
|
||||
#include <utility>
|
||||
|
||||
#include "mimick/mimick.h"
|
||||
#include "rcutils/macros.h"
|
||||
|
||||
namespace mocking_utils
|
||||
{
|
||||
|
||||
/// Mimick specific traits for each mocking_utils::Patch instance.
|
||||
/**
|
||||
* \tparam ID Numerical identifier of the patch. Ought to be unique.
|
||||
* \tparam SignatureT Type of the symbol to be patched.
|
||||
*/
|
||||
template<size_t ID, typename SignatureT>
|
||||
struct PatchTraits;
|
||||
|
||||
/// Traits specialization for ReturnT(void) free functions.
|
||||
/**
|
||||
* \tparam ID Numerical identifier of the patch. Ought to be unique.
|
||||
* \tparam ReturnT Return value type.
|
||||
*/
|
||||
template<size_t ID, typename ReturnT>
|
||||
struct PatchTraits<ID, ReturnT(void)>
|
||||
{
|
||||
mmk_mock_define(mock_type, ReturnT);
|
||||
};
|
||||
|
||||
/// Traits specialization for ReturnT(ArgT0) free functions.
|
||||
/**
|
||||
* \tparam ID Numerical identifier of the patch. Ought to be unique.
|
||||
* \tparam ReturnT Return value type.
|
||||
* \tparam ArgT0 Argument type.
|
||||
*/
|
||||
template<size_t ID, typename ReturnT, typename ArgT0>
|
||||
struct PatchTraits<ID, ReturnT(ArgT0)>
|
||||
{
|
||||
mmk_mock_define(mock_type, ReturnT, ArgT0);
|
||||
};
|
||||
|
||||
/// Traits specialization for ReturnT(ArgT0, ArgT1) free functions.
|
||||
/**
|
||||
* \tparam ID Numerical identifier of the patch. Ought to be unique.
|
||||
* \tparam ReturnT Return value type.
|
||||
* \tparam ArgTx Argument types.
|
||||
*/
|
||||
template<size_t ID, typename ReturnT,
|
||||
typename ArgT0, typename ArgT1>
|
||||
struct PatchTraits<ID, ReturnT(ArgT0, ArgT1)>
|
||||
{
|
||||
mmk_mock_define(mock_type, ReturnT, ArgT0, ArgT1);
|
||||
};
|
||||
|
||||
/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2) free functions.
|
||||
/**
|
||||
* \tparam ID Numerical identifier of the patch. Ought to be unique.
|
||||
* \tparam ReturnT Return value type.
|
||||
* \tparam ArgTx Argument types.
|
||||
*/
|
||||
template<size_t ID, typename ReturnT,
|
||||
typename ArgT0, typename ArgT1, typename ArgT2>
|
||||
struct PatchTraits<ID, ReturnT(ArgT0, ArgT1, ArgT2)>
|
||||
{
|
||||
mmk_mock_define(mock_type, ReturnT, ArgT0, ArgT1, ArgT2);
|
||||
};
|
||||
|
||||
/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2, ArgT3) free functions.
|
||||
/**
|
||||
* \tparam ID Numerical identifier of the patch. Ought to be unique.
|
||||
* \tparam ReturnT Return value type.
|
||||
* \tparam ArgTx Argument types.
|
||||
*/
|
||||
template<size_t ID, typename ReturnT,
|
||||
typename ArgT0, typename ArgT1,
|
||||
typename ArgT2, typename ArgT3>
|
||||
struct PatchTraits<ID, ReturnT(ArgT0, ArgT1, ArgT2, ArgT3)>
|
||||
{
|
||||
mmk_mock_define(mock_type, ReturnT, ArgT0, ArgT1, ArgT2, ArgT3);
|
||||
};
|
||||
|
||||
/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4)
|
||||
/// free functions.
|
||||
/**
|
||||
* \tparam ID Numerical identifier of the patch. Ought to be unique.
|
||||
* \tparam ReturnT Return value type.
|
||||
* \tparam ArgTx Argument types.
|
||||
*/
|
||||
template<size_t ID, typename ReturnT,
|
||||
typename ArgT0, typename ArgT1,
|
||||
typename ArgT2, typename ArgT3, typename ArgT4>
|
||||
struct PatchTraits<ID, ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4)>
|
||||
{
|
||||
mmk_mock_define(mock_type, ReturnT, ArgT0, ArgT1, ArgT2, ArgT3, ArgT4);
|
||||
};
|
||||
|
||||
/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5)
|
||||
/// free functions.
|
||||
/**
|
||||
* \tparam ID Numerical identifier of the patch. Ought to be unique.
|
||||
* \tparam ReturnT Return value type.
|
||||
* \tparam ArgTx Argument types.
|
||||
*/
|
||||
template<size_t ID, typename ReturnT,
|
||||
typename ArgT0, typename ArgT1,
|
||||
typename ArgT2, typename ArgT3,
|
||||
typename ArgT4, typename ArgT5>
|
||||
struct PatchTraits<ID, ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5)>
|
||||
{
|
||||
mmk_mock_define(
|
||||
mock_type, ReturnT, ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5);
|
||||
};
|
||||
|
||||
/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5, ArgT6)
|
||||
/// free functions.
|
||||
/**
|
||||
* \tparam ID Numerical identifier of the patch. Ought to be unique.
|
||||
* \tparam ReturnT Return value type.
|
||||
* \tparam ArgTx Argument types.
|
||||
*/
|
||||
template<size_t ID, typename ReturnT,
|
||||
typename ArgT0, typename ArgT1,
|
||||
typename ArgT2, typename ArgT3,
|
||||
typename ArgT4, typename ArgT5, typename ArgT6>
|
||||
struct PatchTraits<ID, ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5, ArgT6)>
|
||||
{
|
||||
mmk_mock_define(
|
||||
mock_type, ReturnT, ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5, ArgT6);
|
||||
};
|
||||
|
||||
/// Generic trampoline to wrap generalized callables in plain functions.
|
||||
/**
|
||||
* \tparam ID Numerical identifier of this trampoline. Ought to be unique.
|
||||
* \tparam SignatureT Type of the symbol this trampoline replaces.
|
||||
*/
|
||||
template<size_t ID, typename SignatureT>
|
||||
struct Trampoline;
|
||||
|
||||
/// Trampoline specialization for free functions.
|
||||
template<size_t ID, typename ReturnT, typename ... ArgTs>
|
||||
struct Trampoline<ID, ReturnT(ArgTs...)>
|
||||
{
|
||||
static ReturnT base(ArgTs... args)
|
||||
{
|
||||
return target(std::forward<ArgTs>(args)...);
|
||||
}
|
||||
|
||||
static std::function<ReturnT(ArgTs...)> target;
|
||||
};
|
||||
|
||||
template<size_t ID, typename ReturnT, typename ... ArgTs>
|
||||
std::function<ReturnT(ArgTs...)>
|
||||
Trampoline<ID, ReturnT(ArgTs...)>::target;
|
||||
|
||||
/// Setup trampoline with the given @p target.
|
||||
/**
|
||||
* \param[in] target Callable that this trampoline will target.
|
||||
* \return the plain base function of this trampoline.
|
||||
*
|
||||
* \tparam ID Numerical identifier of this trampoline. Ought to be unique.
|
||||
* \tparam SignatureT Type of the symbol this trampoline replaces.
|
||||
*/
|
||||
template<size_t ID, typename SignatureT>
|
||||
auto prepare_trampoline(std::function<SignatureT> target)
|
||||
{
|
||||
Trampoline<ID, SignatureT>::target = target;
|
||||
return Trampoline<ID, SignatureT>::base;
|
||||
}
|
||||
|
||||
/// Patch class for binary API mocking
|
||||
/**
|
||||
* Built on top of Mimick, to enable symbol mocking on a per dynamically
|
||||
* linked binary object basis.
|
||||
*
|
||||
* \tparam ID Numerical identifier for this patch. Ought to be unique.
|
||||
* \tparam SignatureT Type of the symbol to be patched.
|
||||
*/
|
||||
template<size_t ID, typename SignatureT>
|
||||
class Patch;
|
||||
|
||||
/// Patch specialization for ReturnT(ArgTs...) free functions.
|
||||
/**
|
||||
* \tparam ID Numerical identifier for this patch. Ought to be unique.
|
||||
* \tparam ReturnT Return value type.
|
||||
* \tparam ArgTs Argument types.
|
||||
*/
|
||||
template<size_t ID, typename ReturnT, typename ... ArgTs>
|
||||
class Patch<ID, ReturnT(ArgTs...)>
|
||||
{
|
||||
public:
|
||||
using mock_type = typename PatchTraits<ID, ReturnT(ArgTs...)>::mock_type;
|
||||
|
||||
/// Construct a patch.
|
||||
/**
|
||||
* \param[in] target Symbol target string, using Mimick syntax
|
||||
* i.e. "symbol(@scope)?", where scope may be "self" to target the current
|
||||
* binary, "lib:library_name" to target a given library, "file:path/to/library"
|
||||
* to target a given file, or "sym:other_symbol" to target the first library
|
||||
* that defines said symbol.
|
||||
* \param[in] proxy An indirection to call the target function.
|
||||
* This indirection must ensure this call goes through the function's
|
||||
* trampoline, as setup by the dynamic linker.
|
||||
* \return a mocking_utils::Patch instance.
|
||||
*/
|
||||
explicit Patch(const std::string & target, std::function<ReturnT(ArgTs...)> proxy)
|
||||
: target_(target), proxy_(proxy)
|
||||
{
|
||||
}
|
||||
|
||||
// Copy construction and assignment are disabled.
|
||||
Patch(const Patch &) = delete;
|
||||
Patch & operator=(const Patch &) = delete;
|
||||
|
||||
Patch(Patch && other)
|
||||
{
|
||||
mock_ = other.mock_;
|
||||
other.mock_ = nullptr;
|
||||
}
|
||||
|
||||
Patch & operator=(Patch && other)
|
||||
{
|
||||
if (mock_) {
|
||||
mmk_reset(mock_);
|
||||
}
|
||||
mock_ = other.mock_;
|
||||
other.mock_ = nullptr;
|
||||
}
|
||||
|
||||
~Patch()
|
||||
{
|
||||
if (mock_) {
|
||||
mmk_reset(mock_);
|
||||
}
|
||||
}
|
||||
|
||||
/// Inject a @p replacement for the patched function.
|
||||
Patch & then_call(std::function<ReturnT(ArgTs...)> replacement) &
|
||||
{
|
||||
replace_with(replacement);
|
||||
return *this;
|
||||
}
|
||||
|
||||
/// Inject a @p replacement for the patched function.
|
||||
Patch && then_call(std::function<ReturnT(ArgTs...)> replacement) &&
|
||||
{
|
||||
replace_with(replacement);
|
||||
return std::move(*this);
|
||||
}
|
||||
|
||||
private:
|
||||
// Helper for template parameter pack expansion using `mmk_any`
|
||||
// macro as pattern.
|
||||
template<typename T>
|
||||
T any() {return mmk_any(T);}
|
||||
|
||||
void replace_with(std::function<ReturnT(ArgTs...)> replacement)
|
||||
{
|
||||
if (mock_) {
|
||||
throw std::logic_error("Cannot configure patch more than once");
|
||||
}
|
||||
auto type_erased_trampoline =
|
||||
reinterpret_cast<mmk_fn>(prepare_trampoline<ID>(replacement));
|
||||
auto MMK_MANGLE(mock_type, create) =
|
||||
PatchTraits<ID, ReturnT(ArgTs...)>::MMK_MANGLE(mock_type, create);
|
||||
mock_ = mmk_mock(target_.c_str(), mock_type);
|
||||
mmk_when(proxy_(any<ArgTs>()...), .then_call = type_erased_trampoline);
|
||||
}
|
||||
|
||||
mock_type mock_{nullptr};
|
||||
std::string target_;
|
||||
std::function<ReturnT(ArgTs...)> proxy_;
|
||||
};
|
||||
|
||||
/// Make a patch for a `target` function.
|
||||
/**
|
||||
* Useful for type deduction during \ref mocking_utils::Patch construction.
|
||||
*
|
||||
* \param[in] target Symbol target string, using Mimick syntax.
|
||||
* \param[in] proxy An indirection to call the target function.
|
||||
* \return a mocking_utils::Patch instance.
|
||||
*
|
||||
* \tparam ID Numerical identifier for this patch. Ought to be unique.
|
||||
* \tparam SignatureT Type of the function to be patched.
|
||||
*
|
||||
* \sa mocking_utils::Patch for further reference.
|
||||
*/
|
||||
template<size_t ID, typename SignatureT>
|
||||
auto make_patch(const std::string & target, std::function<SignatureT> proxy)
|
||||
{
|
||||
return Patch<ID, SignatureT>(target, proxy);
|
||||
}
|
||||
|
||||
/// Define a dummy operator `op` for a given `type`.
|
||||
/**
|
||||
* Useful to enable patching functions that take arguments whose types
|
||||
* do not define basic comparison operators, as required by Mimick.
|
||||
*/
|
||||
#define MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(type_, op) \
|
||||
template<typename T> \
|
||||
typename std::enable_if<std::is_same<T, type_>::value, bool>::type \
|
||||
operator op(const T &, const T &) { \
|
||||
return false; \
|
||||
}
|
||||
|
||||
/// Get the exact \ref mocking_utils::Patch type for a given `id` and `function`.
|
||||
/**
|
||||
* Useful to avoid ignored attribute warnings when using the \b decltype operator.
|
||||
*/
|
||||
#define MOCKING_UTILS_PATCH_TYPE(id, function) \
|
||||
decltype(mocking_utils::make_patch<id, decltype(function)>("", nullptr))
|
||||
|
||||
/// A transparent forwarding proxy to a given `function`.
|
||||
/**
|
||||
* Useful to ensure a call to `function` goes through its trampoline.
|
||||
*/
|
||||
#define MOCKING_UTILS_PATCH_PROXY(function) \
|
||||
[] (auto && ... args)->decltype(auto) { \
|
||||
return function(std::forward<decltype(args)>(args)...); \
|
||||
}
|
||||
|
||||
/// Compute a Mimick symbol target string based on which `function` is to be patched
|
||||
/// in which `scope`.
|
||||
#define MOCKING_UTILS_PATCH_TARGET(scope, function) \
|
||||
(std::string(RCUTILS_STRINGIFY(function)) + "@" + (scope))
|
||||
|
||||
/// Prepare a mocking_utils::Patch for patching a `function` in a given `scope`
|
||||
/// but defer applying any changes.
|
||||
#define prepare_patch(scope, function) \
|
||||
make_patch<__COUNTER__, decltype(function)>( \
|
||||
MOCKING_UTILS_PATCH_TARGET(scope, function), MOCKING_UTILS_PATCH_PROXY(function) \
|
||||
)
|
||||
|
||||
/// Patch a `function` with a used-provided `replacement` in a given `scope`.
|
||||
#define patch(scope, function, replacement) \
|
||||
prepare_patch(scope, function).then_call(replacement)
|
||||
|
||||
/// Patch a `function` to always yield a given `return_code` in a given `scope`.
|
||||
#define patch_and_return(scope, function, return_code) \
|
||||
patch(scope, function, [&](auto && ...) {return return_code;})
|
||||
|
||||
/// Patch a `function` to execute normally but always yield a given `return_code`
|
||||
/// in a given `scope`.
|
||||
#define inject_on_return(scope, function, return_code) \
|
||||
patch( \
|
||||
scope, function, ([&, base = function](auto && ... __args) { \
|
||||
static_cast<void>(base(std::forward<decltype(__args)>(__args)...)); \
|
||||
return return_code; \
|
||||
}))
|
||||
|
||||
} // namespace mocking_utils
|
||||
|
||||
#ifdef MOCKING_UTILS_SUPPORT_VA_LIST
|
||||
// Define dummy comparison operators for C standard va_list type
|
||||
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(va_list, ==)
|
||||
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(va_list, !=)
|
||||
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(va_list, <)
|
||||
MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(va_list, >)
|
||||
#endif
|
||||
|
||||
#endif // MOCKING_UTILS__PATCH_HPP_
|
|
@ -20,6 +20,7 @@
|
|||
|
||||
#include <rcl_action/names.h>
|
||||
#include <rcl_action/default_qos.h>
|
||||
#include <rcl_action/wait.h>
|
||||
|
||||
#include <rclcpp/clock.hpp>
|
||||
#include <rclcpp/exceptions.hpp>
|
||||
|
@ -46,6 +47,8 @@
|
|||
#include "rclcpp_action/qos.hpp"
|
||||
#include "rclcpp_action/types.hpp"
|
||||
|
||||
#include "./mocking_utils/patch.hpp"
|
||||
|
||||
using namespace std::chrono_literals;
|
||||
|
||||
const auto WAIT_FOR_SERVER_TIMEOUT = 10s;
|
||||
|
@ -324,23 +327,85 @@ TEST_F(TestClient, construction_and_destruction_callback_group)
|
|||
).reset());
|
||||
}
|
||||
|
||||
TEST_F(TestClient, construction_and_destruction_rcl_errors)
|
||||
{
|
||||
{
|
||||
auto mock = mocking_utils::inject_on_return(
|
||||
"lib:rclcpp_action", rcl_action_client_fini, RCL_RET_ERROR);
|
||||
// It just logs an error message and continues
|
||||
EXPECT_NO_THROW(
|
||||
rclcpp_action::create_client<ActionType>(client_node, action_name).reset());
|
||||
}
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_client_init, RCL_RET_ERROR);
|
||||
EXPECT_THROW(
|
||||
rclcpp_action::create_client<ActionType>(client_node, action_name).reset(),
|
||||
rclcpp::exceptions::RCLError);
|
||||
}
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_client_wait_set_get_num_entities, RCL_RET_ERROR);
|
||||
EXPECT_THROW(
|
||||
rclcpp_action::create_client<ActionType>(client_node, action_name),
|
||||
rclcpp::exceptions::RCLError);
|
||||
}
|
||||
}
|
||||
|
||||
TEST_F(TestClient, wait_for_action_server)
|
||||
{
|
||||
auto action_client = rclcpp_action::create_client<ActionType>(client_node, action_name);
|
||||
EXPECT_FALSE(action_client->wait_for_action_server(0ms));
|
||||
EXPECT_FALSE(action_client->wait_for_action_server(100ms));
|
||||
auto future = std::async(
|
||||
std::launch::async, [&action_client]() {
|
||||
return action_client->wait_for_action_server(WAIT_FOR_SERVER_TIMEOUT);
|
||||
});
|
||||
EXPECT_FALSE(action_client->wait_for_action_server(10ms));
|
||||
SetUpServer();
|
||||
EXPECT_TRUE(future.get());
|
||||
ASSERT_TRUE(action_client->wait_for_action_server(WAIT_FOR_SERVER_TIMEOUT));
|
||||
TearDownServer();
|
||||
|
||||
client_node.reset(); // Drop node before action client
|
||||
EXPECT_THROW(action_client->wait_for_action_server(0ms), rclcpp::exceptions::InvalidNodeError);
|
||||
}
|
||||
|
||||
TEST_F(TestClient, wait_for_action_server_rcl_errors)
|
||||
{
|
||||
auto action_client = rclcpp_action::create_client<ActionType>(client_node, action_name);
|
||||
SetUpServer();
|
||||
ASSERT_TRUE(action_client->wait_for_action_server(WAIT_FOR_SERVER_TIMEOUT));
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_server_is_available, RCL_RET_NODE_INVALID);
|
||||
EXPECT_THROW(action_client->action_server_is_ready(), rclcpp::exceptions::RCLError);
|
||||
|
||||
auto mock_context_is_valid = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_context_is_valid, false);
|
||||
EXPECT_FALSE(action_client->action_server_is_ready());
|
||||
}
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_server_is_available, RCL_RET_ERROR);
|
||||
EXPECT_THROW(action_client->action_server_is_ready(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
TearDownServer();
|
||||
}
|
||||
|
||||
TEST_F(TestClient, is_ready) {
|
||||
auto action_client = rclcpp_action::create_client<ActionType>(client_node, action_name);
|
||||
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
auto rcl_context = client_node->get_node_base_interface()->get_context()->get_rcl_context().get();
|
||||
ASSERT_EQ(
|
||||
RCL_RET_OK,
|
||||
rcl_wait_set_init(&wait_set, 10, 10, 10, 10, 10, 10, rcl_context, allocator));
|
||||
ASSERT_TRUE(action_client->add_to_wait_set(&wait_set));
|
||||
EXPECT_TRUE(action_client->is_ready(&wait_set));
|
||||
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_client_wait_set_get_entities_ready, RCL_RET_ERROR);
|
||||
EXPECT_THROW(action_client->is_ready(&wait_set), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
client_node.reset(); // Drop node before action client
|
||||
}
|
||||
|
||||
TEST_F(TestClientAgainstServer, async_send_goal_no_callbacks)
|
||||
{
|
||||
auto action_client = rclcpp_action::create_client<ActionType>(client_node, action_name);
|
||||
|
@ -482,7 +547,7 @@ TEST_F(TestClientAgainstServer, async_send_goal_with_feedback_callback_wait_for_
|
|||
send_goal_ops.feedback_callback =
|
||||
[&feedback_count](
|
||||
typename ActionGoalHandle::SharedPtr goal_handle,
|
||||
const std::shared_ptr<const ActionFeedback> feedback) mutable
|
||||
const std::shared_ptr<const ActionFeedback> feedback)
|
||||
{
|
||||
(void)goal_handle;
|
||||
(void)feedback;
|
||||
|
@ -515,7 +580,7 @@ TEST_F(TestClientAgainstServer, async_send_goal_with_result_callback_wait_for_re
|
|||
auto send_goal_ops = rclcpp_action::Client<ActionType>::SendGoalOptions();
|
||||
send_goal_ops.result_callback =
|
||||
[&result_callback_received](
|
||||
const typename ActionGoalHandle::WrappedResult & result) mutable
|
||||
const typename ActionGoalHandle::WrappedResult & result)
|
||||
{
|
||||
if (
|
||||
rclcpp_action::ResultCode::SUCCEEDED == result.code &&
|
||||
|
@ -557,7 +622,7 @@ TEST_F(TestClientAgainstServer, async_get_result_with_callback)
|
|||
auto future_result = action_client->async_get_result(
|
||||
goal_handle,
|
||||
[&result_callback_received](
|
||||
const typename ActionGoalHandle::WrappedResult & result) mutable
|
||||
const typename ActionGoalHandle::WrappedResult & result)
|
||||
{
|
||||
if (
|
||||
rclcpp_action::ResultCode::SUCCEEDED == result.code &&
|
||||
|
@ -608,7 +673,7 @@ TEST_F(TestClientAgainstServer, async_cancel_one_goal_with_callback)
|
|||
auto future_cancel = action_client->async_cancel_goal(
|
||||
goal_handle,
|
||||
[&cancel_response_received, goal_handle](
|
||||
ActionCancelGoalResponse::SharedPtr response) mutable
|
||||
ActionCancelGoalResponse::SharedPtr response)
|
||||
{
|
||||
if (
|
||||
ActionCancelGoalResponse::ERROR_NONE == response->return_code &&
|
||||
|
@ -785,3 +850,114 @@ TEST_F(TestClientAgainstServer, async_cancel_some_goals_with_callback)
|
|||
EXPECT_EQ(goal_handle0->get_goal_id(), cancel_response->goals_canceling[0].goal_id.uuid);
|
||||
EXPECT_EQ(rclcpp_action::GoalStatus::STATUS_CANCELED, goal_handle0->get_status());
|
||||
}
|
||||
|
||||
TEST_F(TestClientAgainstServer, send_rcl_errors)
|
||||
{
|
||||
auto action_client = rclcpp_action::create_client<ActionType>(client_node, action_name);
|
||||
ASSERT_TRUE(action_client->wait_for_action_server(WAIT_FOR_SERVER_TIMEOUT));
|
||||
|
||||
auto send_goal_ops = rclcpp_action::Client<ActionType>::SendGoalOptions();
|
||||
send_goal_ops.result_callback =
|
||||
[](const typename ActionGoalHandle::WrappedResult &) {};
|
||||
send_goal_ops.feedback_callback =
|
||||
[](typename ActionGoalHandle::SharedPtr,
|
||||
const std::shared_ptr<const ActionFeedback>) {};
|
||||
|
||||
{
|
||||
ActionGoal goal;
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_send_goal_request, RCL_RET_ERROR);
|
||||
EXPECT_THROW(
|
||||
action_client->async_send_goal(goal, send_goal_ops),
|
||||
rclcpp::exceptions::RCLError);
|
||||
}
|
||||
// TODO(anyone): Review this test
|
||||
// {
|
||||
// ActionGoal goal;
|
||||
// auto mock = mocking_utils::patch_and_return(
|
||||
// "lib:rclcpp_action", rcl_action_send_result_request, RCL_RET_ERROR);
|
||||
// auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops);
|
||||
// dual_spin_until_future_complete(future_goal_handle);
|
||||
// auto goal_handle = future_goal_handle.get();
|
||||
// EXPECT_EQ(rclcpp_action::GoalStatus::STATUS_UNKNOWN, goal_handle->get_status());
|
||||
// }
|
||||
{
|
||||
ActionGoal goal;
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_send_cancel_request, RCL_RET_ERROR);
|
||||
auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops);
|
||||
dual_spin_until_future_complete(future_goal_handle);
|
||||
auto goal_handle = future_goal_handle.get();
|
||||
EXPECT_THROW(
|
||||
action_client->async_cancel_goals_before(goal_handle->get_goal_stamp()),
|
||||
rclcpp::exceptions::RCLError);
|
||||
}
|
||||
}
|
||||
|
||||
TEST_F(TestClientAgainstServer, execute_rcl_errors)
|
||||
{
|
||||
auto action_client = rclcpp_action::create_client<ActionType>(client_node, action_name);
|
||||
ASSERT_TRUE(action_client->wait_for_action_server(WAIT_FOR_SERVER_TIMEOUT));
|
||||
|
||||
auto send_goal_ops = rclcpp_action::Client<ActionType>::SendGoalOptions();
|
||||
send_goal_ops.result_callback =
|
||||
[](const typename ActionGoalHandle::WrappedResult &) {};
|
||||
send_goal_ops.feedback_callback =
|
||||
[](typename ActionGoalHandle::SharedPtr,
|
||||
const std::shared_ptr<const ActionFeedback>) {};
|
||||
|
||||
{
|
||||
ActionGoal goal;
|
||||
goal.order = 5;
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_take_feedback, RCL_RET_ERROR);
|
||||
|
||||
auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops);
|
||||
dual_spin_until_future_complete(future_goal_handle);
|
||||
auto goal_handle = future_goal_handle.get();
|
||||
auto future_result = action_client->async_get_result(goal_handle);
|
||||
EXPECT_THROW(
|
||||
dual_spin_until_future_complete(future_result),
|
||||
rclcpp::exceptions::RCLError);
|
||||
}
|
||||
{
|
||||
ActionGoal goal;
|
||||
goal.order = 5;
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_take_goal_response, RCL_RET_ERROR);
|
||||
|
||||
auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops);
|
||||
EXPECT_THROW(
|
||||
dual_spin_until_future_complete(future_goal_handle),
|
||||
rclcpp::exceptions::RCLError);
|
||||
}
|
||||
{
|
||||
ActionGoal goal;
|
||||
goal.order = 5;
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_take_result_response, RCL_RET_ERROR);
|
||||
|
||||
auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops);
|
||||
dual_spin_until_future_complete(future_goal_handle);
|
||||
auto goal_handle = future_goal_handle.get();
|
||||
auto future_result = action_client->async_get_result(goal_handle);
|
||||
EXPECT_THROW(
|
||||
dual_spin_until_future_complete(future_result),
|
||||
rclcpp::exceptions::RCLError);
|
||||
}
|
||||
{
|
||||
ActionGoal goal;
|
||||
goal.order = 5;
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_take_cancel_response, RCL_RET_ERROR);
|
||||
|
||||
auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops);
|
||||
dual_spin_until_future_complete(future_goal_handle);
|
||||
auto goal_handle = future_goal_handle.get();
|
||||
auto future_cancel_some =
|
||||
action_client->async_cancel_goals_before(goal_handle->get_goal_stamp());
|
||||
EXPECT_THROW(
|
||||
dual_spin_until_future_complete(future_cancel_some),
|
||||
rclcpp::exceptions::RCLError);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -15,6 +15,7 @@
|
|||
#include <rclcpp/exceptions.hpp>
|
||||
#include <rclcpp/node.hpp>
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include <rclcpp/scope_exit.hpp>
|
||||
#include <test_msgs/action/fibonacci.hpp>
|
||||
|
||||
#include <gtest/gtest.h>
|
||||
|
@ -22,8 +23,11 @@
|
|||
#include <memory>
|
||||
#include <vector>
|
||||
|
||||
#include "rcl_action/action_server.h"
|
||||
#include "rcl_action/wait.h"
|
||||
#include "rclcpp_action/create_server.hpp"
|
||||
#include "rclcpp_action/server.hpp"
|
||||
#include "./mocking_utils/patch.hpp"
|
||||
|
||||
using Fibonacci = test_msgs::action::Fibonacci;
|
||||
using CancelResponse = typename Fibonacci::Impl::CancelGoalService::Response;
|
||||
|
@ -37,8 +41,15 @@ protected:
|
|||
rclcpp::init(0, nullptr);
|
||||
}
|
||||
|
||||
static void TearDownTestCase()
|
||||
{
|
||||
rclcpp::shutdown();
|
||||
}
|
||||
|
||||
std::shared_ptr<Fibonacci::Impl::SendGoalService::Request>
|
||||
send_goal_request(rclcpp::Node::SharedPtr node, GoalUUID uuid)
|
||||
send_goal_request(
|
||||
rclcpp::Node::SharedPtr node, GoalUUID uuid,
|
||||
std::chrono::milliseconds timeout = std::chrono::milliseconds(-1))
|
||||
{
|
||||
auto client = node->create_client<Fibonacci::Impl::SendGoalService>(
|
||||
"fibonacci/_action/send_goal");
|
||||
|
@ -48,17 +59,20 @@ protected:
|
|||
auto request = std::make_shared<Fibonacci::Impl::SendGoalService::Request>();
|
||||
request->goal_id.uuid = uuid;
|
||||
auto future = client->async_send_request(request);
|
||||
if (
|
||||
rclcpp::FutureReturnCode::SUCCESS !=
|
||||
rclcpp::spin_until_future_complete(node, future))
|
||||
{
|
||||
auto return_code = rclcpp::spin_until_future_complete(node, future, timeout);
|
||||
if (rclcpp::FutureReturnCode::SUCCESS == return_code) {
|
||||
return request;
|
||||
} else if (rclcpp::FutureReturnCode::TIMEOUT == return_code) {
|
||||
throw std::runtime_error("send goal future timed out");
|
||||
} else {
|
||||
throw std::runtime_error("send goal future didn't complete succesfully");
|
||||
}
|
||||
return request;
|
||||
}
|
||||
|
||||
CancelResponse::SharedPtr
|
||||
send_cancel_request(rclcpp::Node::SharedPtr node, GoalUUID uuid)
|
||||
send_cancel_request(
|
||||
rclcpp::Node::SharedPtr node, GoalUUID uuid,
|
||||
std::chrono::milliseconds timeout = std::chrono::milliseconds(-1))
|
||||
{
|
||||
auto cancel_client = node->create_client<Fibonacci::Impl::CancelGoalService>(
|
||||
"fibonacci/_action/cancel_goal");
|
||||
|
@ -68,13 +82,14 @@ protected:
|
|||
auto request = std::make_shared<Fibonacci::Impl::CancelGoalService::Request>();
|
||||
request->goal_info.goal_id.uuid = uuid;
|
||||
auto future = cancel_client->async_send_request(request);
|
||||
if (
|
||||
rclcpp::FutureReturnCode::SUCCESS !=
|
||||
rclcpp::spin_until_future_complete(node, future))
|
||||
{
|
||||
throw std::runtime_error("cancel goal future didn't complete succesfully");
|
||||
}
|
||||
auto return_code = rclcpp::spin_until_future_complete(node, future, timeout);
|
||||
if (rclcpp::FutureReturnCode::SUCCESS == return_code) {
|
||||
return future.get();
|
||||
} else if (rclcpp::FutureReturnCode::TIMEOUT == return_code) {
|
||||
throw std::runtime_error("cancel request future timed out");
|
||||
} else {
|
||||
throw std::runtime_error("cancel request future didn't complete succesfully");
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -146,6 +161,50 @@ TEST_F(TestServer, construction_and_destruction_callback_group)
|
|||
group));
|
||||
}
|
||||
|
||||
TEST_F(TestServer, construction_and_destruction_server_init_error)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_server_init, RCL_RET_ERROR);
|
||||
auto node = std::make_shared<rclcpp::Node>("construct_node", "/rclcpp_action/construct");
|
||||
|
||||
EXPECT_THROW(
|
||||
{
|
||||
using GoalHandle = rclcpp_action::ServerGoalHandle<Fibonacci>;
|
||||
auto as = rclcpp_action::create_server<Fibonacci>(
|
||||
node, "fibonacci",
|
||||
[](const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>) {
|
||||
return rclcpp_action::GoalResponse::REJECT;
|
||||
},
|
||||
[](std::shared_ptr<GoalHandle>) {
|
||||
return rclcpp_action::CancelResponse::REJECT;
|
||||
},
|
||||
[](std::shared_ptr<GoalHandle>) {});
|
||||
(void)as;
|
||||
}, rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestServer, construction_and_destruction_wait_set_error)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_server_wait_set_get_num_entities, RCL_RET_ERROR);
|
||||
auto node = std::make_shared<rclcpp::Node>("construct_node", "/rclcpp_action/construct");
|
||||
|
||||
EXPECT_THROW(
|
||||
{
|
||||
using GoalHandle = rclcpp_action::ServerGoalHandle<Fibonacci>;
|
||||
auto as = rclcpp_action::create_server<Fibonacci>(
|
||||
node, "fibonacci",
|
||||
[](const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>) {
|
||||
return rclcpp_action::GoalResponse::REJECT;
|
||||
},
|
||||
[](std::shared_ptr<GoalHandle>) {
|
||||
return rclcpp_action::CancelResponse::REJECT;
|
||||
},
|
||||
[](std::shared_ptr<GoalHandle>) {});
|
||||
(void)as;
|
||||
}, rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestServer, handle_goal_called)
|
||||
{
|
||||
auto node = std::make_shared<rclcpp::Node>("handle_goal_node", "/rclcpp_action/handle_goal");
|
||||
|
@ -923,3 +982,238 @@ TEST_F(TestServer, deferred_execution)
|
|||
received_handle->execute();
|
||||
EXPECT_TRUE(received_handle->is_executing());
|
||||
}
|
||||
|
||||
class TestBasicServer : public TestServer
|
||||
{
|
||||
public:
|
||||
void SetUp()
|
||||
{
|
||||
node_ = std::make_shared<rclcpp::Node>("goal_request", "/rclcpp_action/goal_request");
|
||||
uuid_ = {{1, 2, 3, 4, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}};
|
||||
action_server_ = rclcpp_action::create_server<Fibonacci>(
|
||||
node_, "fibonacci",
|
||||
[](const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>) {
|
||||
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
|
||||
},
|
||||
[](std::shared_ptr<GoalHandle>) {
|
||||
return rclcpp_action::CancelResponse::ACCEPT;
|
||||
},
|
||||
[this](std::shared_ptr<GoalHandle> handle) {
|
||||
goal_handle_ = handle;
|
||||
});
|
||||
}
|
||||
|
||||
void SendClientGoalRequest(
|
||||
std::chrono::milliseconds timeout = std::chrono::milliseconds(-1))
|
||||
{
|
||||
send_goal_request(node_, uuid_, timeout);
|
||||
auto result_client = node_->create_client<Fibonacci::Impl::GetResultService>(
|
||||
"fibonacci/_action/get_result");
|
||||
if (!result_client->wait_for_service(std::chrono::seconds(20))) {
|
||||
throw std::runtime_error("get result service didn't become available");
|
||||
}
|
||||
auto request = std::make_shared<Fibonacci::Impl::GetResultService::Request>();
|
||||
request->goal_id.uuid = uuid_;
|
||||
auto future = result_client->async_send_request(request);
|
||||
|
||||
// Send a result
|
||||
auto result = std::make_shared<Fibonacci::Result>();
|
||||
result->sequence = {5, 8, 13, 21};
|
||||
goal_handle_->succeed(result);
|
||||
|
||||
// Wait for the result request to be received
|
||||
ASSERT_EQ(
|
||||
rclcpp::FutureReturnCode::SUCCESS,
|
||||
rclcpp::spin_until_future_complete(node_, future));
|
||||
|
||||
auto response = future.get();
|
||||
EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_SUCCEEDED, response->status);
|
||||
EXPECT_EQ(result->sequence, response->result.sequence);
|
||||
|
||||
// Wait for goal expiration
|
||||
rclcpp::sleep_for(std::chrono::milliseconds(100));
|
||||
|
||||
// Allow for expiration to take place
|
||||
rclcpp::spin_some(node_);
|
||||
|
||||
// Send and wait for another result request
|
||||
future = result_client->async_send_request(request);
|
||||
ASSERT_EQ(
|
||||
rclcpp::FutureReturnCode::SUCCESS,
|
||||
rclcpp::spin_until_future_complete(node_, future));
|
||||
}
|
||||
|
||||
protected:
|
||||
GoalUUID uuid_;
|
||||
std::shared_ptr<rclcpp::Node> node_;
|
||||
std::shared_ptr<rclcpp_action::Server<Fibonacci>> action_server_;
|
||||
|
||||
using GoalHandle = rclcpp_action::ServerGoalHandle<Fibonacci>;
|
||||
std::shared_ptr<GoalHandle> goal_handle_;
|
||||
};
|
||||
|
||||
class TestGoalRequestServer : public TestBasicServer {};
|
||||
|
||||
TEST_F(TestGoalRequestServer, execute_goal_request_received_take_goal)
|
||||
{
|
||||
EXPECT_NO_THROW(SendClientGoalRequest());
|
||||
}
|
||||
|
||||
class TestCancelRequestServer : public TestBasicServer
|
||||
{
|
||||
public:
|
||||
void SendClientCancelRequest(
|
||||
std::chrono::milliseconds timeout = std::chrono::milliseconds(-1))
|
||||
{
|
||||
send_goal_request(node_, uuid_, timeout);
|
||||
send_cancel_request(node_, uuid_, timeout);
|
||||
}
|
||||
};
|
||||
|
||||
TEST_F(TestCancelRequestServer, execute_goal_request_received_take_goal)
|
||||
{
|
||||
EXPECT_NO_THROW(SendClientCancelRequest());
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, is_ready_rcl_error) {
|
||||
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
auto rcl_context = node_->get_node_base_interface()->get_context()->get_rcl_context().get();
|
||||
ASSERT_EQ(
|
||||
RCL_RET_OK,
|
||||
rcl_wait_set_init(&wait_set, 10, 10, 10, 10, 10, 10, rcl_context, allocator));
|
||||
RCLCPP_SCOPE_EXIT(
|
||||
{
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_wait_set_fini(&wait_set));
|
||||
});
|
||||
ASSERT_TRUE(action_server_->add_to_wait_set(&wait_set));
|
||||
|
||||
EXPECT_TRUE(action_server_->is_ready(&wait_set));
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_server_wait_set_get_entities_ready, RCL_RET_ERROR);
|
||||
EXPECT_THROW(action_server_->is_ready(&wait_set), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, execute_goal_request_received_take_goal_request_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_take_goal_request, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, execute_goal_request_received_send_goal_response_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_send_goal_response, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, execute_goal_request_received_accept_new_goal_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_accept_new_goal, nullptr);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), std::runtime_error);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, execute_goal_request_received_update_goal_state_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_update_goal_state, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, publish_status_server_get_goal_handles_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_server_get_goal_handles, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, publish_status_get_goal_status_array_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_get_goal_status_array, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, publish_status_publish_status_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_publish_status, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), std::runtime_error);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, execute_goal_request_received_take_failed)
|
||||
{
|
||||
auto mock = mocking_utils::inject_on_return(
|
||||
"lib:rclcpp_action", rcl_action_take_goal_request, RCL_RET_ACTION_SERVER_TAKE_FAILED);
|
||||
try {
|
||||
SendClientGoalRequest(std::chrono::milliseconds(100));
|
||||
ADD_FAILURE() << "SetupActionServerAndSpin did not throw, but was expected to";
|
||||
} catch (const std::runtime_error & e) {
|
||||
EXPECT_STREQ("send goal future timed out", e.what());
|
||||
} catch (...) {
|
||||
ADD_FAILURE() << "SetupActionServerAndSpin threw, but not the expected std::runtime_error";
|
||||
}
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, get_result_rcl_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_take_result_request, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestGoalRequestServer, send_result_rcl_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_send_result_response, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientGoalRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestCancelRequestServer, execute_cancel_request_received_take_cancel_request_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_take_cancel_request, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientCancelRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestCancelRequestServer, execute_cancel_request_received_take_failed)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_take_cancel_request, RCL_RET_ACTION_SERVER_TAKE_FAILED);
|
||||
try {
|
||||
SendClientCancelRequest(std::chrono::milliseconds(100));
|
||||
ADD_FAILURE() << "SetupActionServerAndSpin did not throw, but it was expected to";
|
||||
} catch (const std::runtime_error & e) {
|
||||
EXPECT_STREQ("cancel request future timed out", e.what());
|
||||
} catch (...) {
|
||||
ADD_FAILURE() << "SetupActionServerAndSpin threw, but not the expected std::runtime_error";
|
||||
}
|
||||
}
|
||||
|
||||
TEST_F(TestCancelRequestServer, publish_status_rcl_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_process_cancel_request, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientCancelRequest(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestCancelRequestServer, publish_status_send_cancel_response_errors)
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_send_cancel_response, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(SendClientCancelRequest(), std::runtime_error);
|
||||
}
|
||||
|
|
159
rclcpp_action/test/test_server_goal_handle.cpp
Normal file
159
rclcpp_action/test/test_server_goal_handle.cpp
Normal file
|
@ -0,0 +1,159 @@
|
|||
// 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 <rclcpp/exceptions.hpp>
|
||||
#include <rclcpp/node.hpp>
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include <test_msgs/action/fibonacci.hpp>
|
||||
|
||||
#include <gtest/gtest.h>
|
||||
|
||||
#include <memory>
|
||||
#include <vector>
|
||||
|
||||
#include "action_msgs/msg/goal_info.h"
|
||||
#include "rclcpp_action/server_goal_handle.hpp"
|
||||
#include "./mocking_utils/patch.hpp"
|
||||
|
||||
class FibonacciServerGoalHandle
|
||||
: public rclcpp_action::ServerGoalHandle<test_msgs::action::Fibonacci>
|
||||
{
|
||||
public:
|
||||
FibonacciServerGoalHandle(
|
||||
std::shared_ptr<rcl_action_goal_handle_t> rcl_handle,
|
||||
rclcpp_action::GoalUUID uuid,
|
||||
std::shared_ptr<const test_msgs::action::Fibonacci::Goal> goal,
|
||||
std::function<void(
|
||||
const rclcpp_action::GoalUUID &, std::shared_ptr<void>)> on_terminal_state,
|
||||
std::function<void(const rclcpp_action::GoalUUID &)> on_executing,
|
||||
std::function<void(
|
||||
std::shared_ptr<test_msgs::action::Fibonacci::Impl::FeedbackMessage>)> publish_feedback)
|
||||
: rclcpp_action::ServerGoalHandle<test_msgs::action::Fibonacci>(
|
||||
rcl_handle, uuid, goal, on_terminal_state, on_executing, publish_feedback) {}
|
||||
|
||||
bool try_cancel() {return try_canceling();}
|
||||
|
||||
void cancel_goal() {_cancel_goal();}
|
||||
};
|
||||
|
||||
class TestServerGoalHandle : public ::testing::Test
|
||||
{
|
||||
public:
|
||||
TestServerGoalHandle()
|
||||
: handle_(nullptr) {}
|
||||
|
||||
void SetUp()
|
||||
{
|
||||
std::shared_ptr<rcl_action_goal_handle_t> rcl_handle =
|
||||
std::make_shared<rcl_action_goal_handle_t>();
|
||||
*rcl_handle.get() = rcl_action_get_zero_initialized_goal_handle();
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
rcl_action_goal_info_t goal_info = rcl_action_get_zero_initialized_goal_info();
|
||||
ASSERT_EQ(RCL_RET_OK, rcl_action_goal_handle_init(rcl_handle.get(), &goal_info, allocator));
|
||||
rclcpp_action::GoalUUID uuid;
|
||||
std::shared_ptr<const test_msgs::action::Fibonacci::Goal> goal =
|
||||
std::make_shared<const test_msgs::action::Fibonacci::Goal>();
|
||||
auto on_terminal_state = [](const rclcpp_action::GoalUUID &, std::shared_ptr<void>) {};
|
||||
auto on_executing = [](const rclcpp_action::GoalUUID &) {};
|
||||
auto publish_feedback =
|
||||
[](std::shared_ptr<test_msgs::action::Fibonacci::Impl::FeedbackMessage>) {};
|
||||
handle_ = std::make_unique<FibonacciServerGoalHandle>(
|
||||
rcl_handle, uuid, goal, on_terminal_state, on_executing, publish_feedback);
|
||||
}
|
||||
|
||||
protected:
|
||||
std::unique_ptr<FibonacciServerGoalHandle> handle_;
|
||||
};
|
||||
|
||||
TEST_F(TestServerGoalHandle, construct_destruct) {
|
||||
EXPECT_FALSE(handle_->is_canceling());
|
||||
EXPECT_TRUE(handle_->is_active());
|
||||
EXPECT_FALSE(handle_->is_executing());
|
||||
}
|
||||
|
||||
TEST_F(TestServerGoalHandle, cancel) {
|
||||
handle_->execute();
|
||||
EXPECT_TRUE(handle_->try_cancel());
|
||||
EXPECT_FALSE(handle_->is_canceling());
|
||||
EXPECT_FALSE(handle_->is_active());
|
||||
EXPECT_FALSE(handle_->is_executing());
|
||||
|
||||
{
|
||||
auto mock_get_status = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_goal_handle_get_status, RCL_RET_ERROR);
|
||||
EXPECT_FALSE(handle_->try_cancel());
|
||||
}
|
||||
|
||||
{
|
||||
auto mock_update_status = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_update_goal_state, RCL_RET_ERROR);
|
||||
auto mock_is_cancelable = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_goal_handle_is_cancelable, true);
|
||||
EXPECT_FALSE(handle_->try_cancel());
|
||||
EXPECT_THROW(handle_->cancel_goal(), rclcpp::exceptions::RCLError);
|
||||
|
||||
test_msgs::action::Fibonacci::Result::SharedPtr result =
|
||||
std::make_shared<test_msgs::action::Fibonacci::Result>();
|
||||
EXPECT_THROW(handle_->canceled(result), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
}
|
||||
|
||||
TEST_F(TestServerGoalHandle, abort) {
|
||||
handle_->execute();
|
||||
test_msgs::action::Fibonacci::Result::SharedPtr result =
|
||||
std::make_shared<test_msgs::action::Fibonacci::Result>();
|
||||
handle_->abort(result);
|
||||
EXPECT_FALSE(handle_->is_canceling());
|
||||
EXPECT_FALSE(handle_->is_active());
|
||||
EXPECT_FALSE(handle_->is_executing());
|
||||
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_update_goal_state, RCL_RET_ERROR);
|
||||
EXPECT_THROW(handle_->abort(result), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestServerGoalHandle, succeed) {
|
||||
handle_->execute();
|
||||
test_msgs::action::Fibonacci::Result::SharedPtr result =
|
||||
std::make_shared<test_msgs::action::Fibonacci::Result>();
|
||||
handle_->succeed(result);
|
||||
EXPECT_FALSE(handle_->is_canceling());
|
||||
EXPECT_FALSE(handle_->is_active());
|
||||
EXPECT_FALSE(handle_->is_executing());
|
||||
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_update_goal_state, RCL_RET_ERROR);
|
||||
EXPECT_THROW(handle_->succeed(result), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
|
||||
TEST_F(TestServerGoalHandle, execute) {
|
||||
handle_->execute();
|
||||
EXPECT_FALSE(handle_->is_canceling());
|
||||
EXPECT_TRUE(handle_->is_active());
|
||||
EXPECT_TRUE(handle_->is_executing());
|
||||
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_update_goal_state, RCL_RET_ERROR);
|
||||
EXPECT_THROW(handle_->execute(), rclcpp::exceptions::RCLError);
|
||||
}
|
||||
|
||||
TEST_F(TestServerGoalHandle, rcl_action_goal_handle_get_status_error) {
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rclcpp_action", rcl_action_goal_handle_get_status, RCL_RET_ERROR);
|
||||
|
||||
EXPECT_THROW(handle_->is_canceling(), rclcpp::exceptions::RCLError);
|
||||
EXPECT_NO_THROW(handle_->is_active());
|
||||
EXPECT_THROW(handle_->is_executing(), rclcpp::exceptions::RCLError);
|
||||
}
|
Loading…
Add table
Add a link
Reference in a new issue