Add coverage for missing API (except executors) (#1326)
* Add coverage for missing API (except executors Signed-off-by: Stephen Brawner <brawner@gmail.com> * PR Fixup Signed-off-by: Stephen Brawner <brawner@gmail.com> * Do not check state Signed-off-by: Stephen Brawner <brawner@gmail.com>
This commit is contained in:
parent
0312defbc5
commit
b451425ce6
10 changed files with 366 additions and 0 deletions
|
@ -17,6 +17,25 @@ rosidl_generate_interfaces(${PROJECT_NAME}_test_msgs
|
||||||
SKIP_INSTALL
|
SKIP_INSTALL
|
||||||
)
|
)
|
||||||
|
|
||||||
|
ament_add_gtest(
|
||||||
|
test_allocator_common
|
||||||
|
rclcpp/allocator/test_allocator_common.cpp)
|
||||||
|
if(TARGET test_allocator_common)
|
||||||
|
target_link_libraries(test_allocator_common ${PROJECT_NAME})
|
||||||
|
endif()
|
||||||
|
ament_add_gtest(
|
||||||
|
test_allocator_deleter
|
||||||
|
rclcpp/allocator/test_allocator_deleter.cpp)
|
||||||
|
if(TARGET test_allocator_deleter)
|
||||||
|
target_link_libraries(test_allocator_deleter ${PROJECT_NAME})
|
||||||
|
endif()
|
||||||
|
ament_add_gtest(
|
||||||
|
test_exceptions
|
||||||
|
rclcpp/exceptions/test_exceptions.cpp)
|
||||||
|
if(TARGET test_exceptions)
|
||||||
|
target_link_libraries(test_exceptions ${PROJECT_NAME} mimick)
|
||||||
|
endif()
|
||||||
|
|
||||||
# Increasing timeout because connext can take a long time to destroy nodes
|
# Increasing timeout because connext can take a long time to destroy nodes
|
||||||
# TODO(brawner) remove when destroying Node for Connext is resolved. See:
|
# TODO(brawner) remove when destroying Node for Connext is resolved. See:
|
||||||
# https://github.com/ros2/rclcpp/issues/1250
|
# https://github.com/ros2/rclcpp/issues/1250
|
||||||
|
@ -102,6 +121,12 @@ if(TARGET test_function_traits)
|
||||||
"rosidl_typesupport_cpp"
|
"rosidl_typesupport_cpp"
|
||||||
)
|
)
|
||||||
endif()
|
endif()
|
||||||
|
ament_add_gtest(
|
||||||
|
test_future_return_code
|
||||||
|
rclcpp/test_future_return_code.cpp)
|
||||||
|
if(TARGET test_future_return_code)
|
||||||
|
target_link_libraries(test_future_return_code ${PROJECT_NAME})
|
||||||
|
endif()
|
||||||
ament_add_gmock(test_intra_process_manager rclcpp/test_intra_process_manager.cpp)
|
ament_add_gmock(test_intra_process_manager rclcpp/test_intra_process_manager.cpp)
|
||||||
if(TARGET test_intra_process_manager)
|
if(TARGET test_intra_process_manager)
|
||||||
ament_target_dependencies(test_intra_process_manager
|
ament_target_dependencies(test_intra_process_manager
|
||||||
|
|
67
rclcpp/test/rclcpp/allocator/test_allocator_common.cpp
Normal file
67
rclcpp/test/rclcpp/allocator/test_allocator_common.cpp
Normal file
|
@ -0,0 +1,67 @@
|
||||||
|
// 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 <memory>
|
||||||
|
|
||||||
|
#include "rclcpp/allocator/allocator_common.hpp"
|
||||||
|
|
||||||
|
TEST(TestAllocatorCommon, retyped_allocate) {
|
||||||
|
std::allocator<int> allocator;
|
||||||
|
void * untyped_allocator = &allocator;
|
||||||
|
void * allocated_mem =
|
||||||
|
rclcpp::allocator::retyped_allocate<std::allocator<char>>(1u, untyped_allocator);
|
||||||
|
ASSERT_NE(nullptr, allocated_mem);
|
||||||
|
|
||||||
|
auto code = [&untyped_allocator, allocated_mem]() {
|
||||||
|
rclcpp::allocator::retyped_deallocate<int, std::allocator<int>>(
|
||||||
|
allocated_mem, untyped_allocator);
|
||||||
|
};
|
||||||
|
EXPECT_NO_THROW(code());
|
||||||
|
|
||||||
|
allocated_mem = allocator.allocate(1);
|
||||||
|
ASSERT_NE(nullptr, allocated_mem);
|
||||||
|
void * reallocated_mem =
|
||||||
|
rclcpp::allocator::retyped_reallocate<int, std::allocator<int>>(
|
||||||
|
allocated_mem, 2u, untyped_allocator);
|
||||||
|
ASSERT_NE(nullptr, reallocated_mem);
|
||||||
|
|
||||||
|
auto code2 = [&untyped_allocator, reallocated_mem]() {
|
||||||
|
rclcpp::allocator::retyped_deallocate<int, std::allocator<int>>(
|
||||||
|
reallocated_mem, untyped_allocator);
|
||||||
|
};
|
||||||
|
EXPECT_NO_THROW(code2());
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST(TestAllocatorCommon, get_rcl_allocator) {
|
||||||
|
std::allocator<int> allocator;
|
||||||
|
auto rcl_allocator = rclcpp::allocator::get_rcl_allocator<int>(allocator);
|
||||||
|
EXPECT_NE(nullptr, rcl_allocator.allocate);
|
||||||
|
EXPECT_NE(nullptr, rcl_allocator.deallocate);
|
||||||
|
EXPECT_NE(nullptr, rcl_allocator.reallocate);
|
||||||
|
EXPECT_NE(nullptr, rcl_allocator.zero_allocate);
|
||||||
|
// Not testing state as that may or may not be null depending on platform
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST(TestAllocatorCommon, get_void_rcl_allocator) {
|
||||||
|
std::allocator<void> allocator;
|
||||||
|
auto rcl_allocator =
|
||||||
|
rclcpp::allocator::get_rcl_allocator<void, std::allocator<void>>(allocator);
|
||||||
|
EXPECT_NE(nullptr, rcl_allocator.allocate);
|
||||||
|
EXPECT_NE(nullptr, rcl_allocator.deallocate);
|
||||||
|
EXPECT_NE(nullptr, rcl_allocator.reallocate);
|
||||||
|
EXPECT_NE(nullptr, rcl_allocator.zero_allocate);
|
||||||
|
// Not testing state as that may or may not be null depending on platform
|
||||||
|
}
|
101
rclcpp/test/rclcpp/allocator/test_allocator_deleter.cpp
Normal file
101
rclcpp/test/rclcpp/allocator/test_allocator_deleter.cpp
Normal file
|
@ -0,0 +1,101 @@
|
||||||
|
// 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 <memory>
|
||||||
|
|
||||||
|
#include "rclcpp/allocator/allocator_deleter.hpp"
|
||||||
|
|
||||||
|
#include "../../utils/rclcpp_gtest_macros.hpp"
|
||||||
|
|
||||||
|
TEST(TestAllocatorDeleter, construct_destruct) {
|
||||||
|
std::allocator<int> allocator;
|
||||||
|
|
||||||
|
rclcpp::allocator::AllocatorDeleter<std::allocator<int>> deleter;
|
||||||
|
EXPECT_EQ(nullptr, deleter.get_allocator());
|
||||||
|
deleter.set_allocator(&allocator);
|
||||||
|
EXPECT_EQ(&allocator, deleter.get_allocator());
|
||||||
|
|
||||||
|
rclcpp::allocator::AllocatorDeleter<std::allocator<int>> deleter2(&allocator);
|
||||||
|
EXPECT_EQ(&allocator, deleter2.get_allocator());
|
||||||
|
|
||||||
|
rclcpp::allocator::AllocatorDeleter<std::allocator<int>> deleter3(deleter2);
|
||||||
|
EXPECT_EQ(&allocator, deleter3.get_allocator());
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST(TestAllocatorDeleter, delete) {
|
||||||
|
std::allocator<int> allocator;
|
||||||
|
int * some_mem = allocator.allocate(1u);
|
||||||
|
ASSERT_NE(nullptr, some_mem);
|
||||||
|
|
||||||
|
rclcpp::allocator::AllocatorDeleter<std::allocator<int>> deleter(&allocator);
|
||||||
|
EXPECT_NO_THROW(deleter(some_mem));
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST(TestAllocatorDeleter, set_allocator_for_deleter_AllocatorDeleter) {
|
||||||
|
using AllocatorT = std::allocator<int>;
|
||||||
|
using DeleterT = rclcpp::allocator::AllocatorDeleter<AllocatorT>;
|
||||||
|
AllocatorT allocator;
|
||||||
|
DeleterT deleter(&allocator);
|
||||||
|
|
||||||
|
std::allocator<int> allocator2;
|
||||||
|
rclcpp::allocator::set_allocator_for_deleter<AllocatorT, AllocatorT>(&deleter, &allocator2);
|
||||||
|
EXPECT_EQ(&allocator2, deleter.get_allocator());
|
||||||
|
|
||||||
|
auto throwing_statement = [&allocator]() {
|
||||||
|
DeleterT * null_del_ptr = nullptr;
|
||||||
|
rclcpp::allocator::set_allocator_for_deleter<AllocatorT, AllocatorT>(
|
||||||
|
null_del_ptr, &allocator);
|
||||||
|
};
|
||||||
|
RCLCPP_EXPECT_THROW_EQ(
|
||||||
|
throwing_statement(),
|
||||||
|
std::invalid_argument("Argument was NULL to set_allocator_for_deleter"));
|
||||||
|
|
||||||
|
auto throwing_statement2 = [&deleter]() {
|
||||||
|
AllocatorT * null_alloc_ptr = nullptr;
|
||||||
|
rclcpp::allocator::set_allocator_for_deleter<AllocatorT, AllocatorT>(
|
||||||
|
&deleter, null_alloc_ptr);
|
||||||
|
};
|
||||||
|
|
||||||
|
RCLCPP_EXPECT_THROW_EQ(
|
||||||
|
throwing_statement2(),
|
||||||
|
std::invalid_argument("Argument was NULL to set_allocator_for_deleter"));
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST(TestAllocatorDeleter, set_allocator_for_deleter_std_default_delete) {
|
||||||
|
using AllocatorT = std::allocator<int>;
|
||||||
|
using DeleterT = std::default_delete<int>;
|
||||||
|
auto not_throwing_statement = []() {
|
||||||
|
AllocatorT allocator;
|
||||||
|
DeleterT deleter;
|
||||||
|
rclcpp::allocator::set_allocator_for_deleter<int, int>(&deleter, &allocator);
|
||||||
|
};
|
||||||
|
EXPECT_NO_THROW(not_throwing_statement());
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST(TestAllocatorDeleter, set_allocator_for_deleter_unexpected_template) {
|
||||||
|
class SomeAllocatorClass {};
|
||||||
|
class SomeDeleterClass {};
|
||||||
|
using AllocatorT = SomeAllocatorClass;
|
||||||
|
using DeleterT = SomeDeleterClass;
|
||||||
|
auto throwing_statement = []() {
|
||||||
|
DeleterT deleter;
|
||||||
|
AllocatorT allocator;
|
||||||
|
rclcpp::allocator::set_allocator_for_deleter<AllocatorT, int, DeleterT>(&deleter, &allocator);
|
||||||
|
};
|
||||||
|
RCLCPP_EXPECT_THROW_EQ(
|
||||||
|
throwing_statement(),
|
||||||
|
std::runtime_error("Reached unexpected template specialization"));
|
||||||
|
}
|
58
rclcpp/test/rclcpp/exceptions/test_exceptions.cpp
Normal file
58
rclcpp/test/rclcpp/exceptions/test_exceptions.cpp
Normal file
|
@ -0,0 +1,58 @@
|
||||||
|
// 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 "rclcpp/exceptions/exceptions.hpp"
|
||||||
|
#include "rclcpp/rclcpp.hpp"
|
||||||
|
|
||||||
|
#include "../../mocking_utils/patch.hpp"
|
||||||
|
#include "../../utils/rclcpp_gtest_macros.hpp"
|
||||||
|
|
||||||
|
TEST(TestExceptions, throw_from_rcl_error) {
|
||||||
|
EXPECT_THROW(
|
||||||
|
rclcpp::exceptions::throw_from_rcl_error(RCL_RET_BAD_ALLOC, ""),
|
||||||
|
rclcpp::exceptions::RCLBadAlloc);
|
||||||
|
|
||||||
|
EXPECT_THROW(
|
||||||
|
rclcpp::exceptions::throw_from_rcl_error(RCL_RET_INVALID_ARGUMENT, ""),
|
||||||
|
rclcpp::exceptions::RCLInvalidArgument);
|
||||||
|
|
||||||
|
EXPECT_THROW(
|
||||||
|
rclcpp::exceptions::throw_from_rcl_error(RCL_RET_INVALID_ROS_ARGS, ""),
|
||||||
|
rclcpp::exceptions::RCLInvalidROSArgsError);
|
||||||
|
|
||||||
|
EXPECT_THROW(
|
||||||
|
rclcpp::exceptions::throw_from_rcl_error(RCL_RET_ERROR, ""),
|
||||||
|
rclcpp::exceptions::RCLError);
|
||||||
|
|
||||||
|
RCLCPP_EXPECT_THROW_EQ(
|
||||||
|
rclcpp::exceptions::throw_from_rcl_error(RCL_RET_OK, ""),
|
||||||
|
std::invalid_argument("ret is RCL_RET_OK"));
|
||||||
|
|
||||||
|
{
|
||||||
|
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_get_error_state, nullptr);
|
||||||
|
RCLCPP_EXPECT_THROW_EQ(
|
||||||
|
rclcpp::exceptions::throw_from_rcl_error(RCL_RET_ERROR, ""),
|
||||||
|
std::runtime_error("rcl error state is not set"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST(TestExceptions, basic_constructors) {
|
||||||
|
EXPECT_STREQ("node is invalid", rclcpp::exceptions::InvalidNodeError().what());
|
||||||
|
rcl_error_state_t error_state{"error", __FILE__, __LINE__};
|
||||||
|
EXPECT_STREQ(
|
||||||
|
"prefix: error not set",
|
||||||
|
rclcpp::exceptions::RCLInvalidROSArgsError(RCL_RET_ERROR, &error_state, "prefix: ").what());
|
||||||
|
}
|
34
rclcpp/test/rclcpp/test_future_return_code.cpp
Normal file
34
rclcpp/test/rclcpp/test_future_return_code.cpp
Normal file
|
@ -0,0 +1,34 @@
|
||||||
|
// Copyright 2015 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 <string>
|
||||||
|
|
||||||
|
#include "rclcpp/future_return_code.hpp"
|
||||||
|
|
||||||
|
TEST(TestFutureReturnCode, to_string) {
|
||||||
|
EXPECT_EQ(
|
||||||
|
"Unknown enum value (-1)", rclcpp::to_string(rclcpp::FutureReturnCode(-1)));
|
||||||
|
EXPECT_EQ(
|
||||||
|
"SUCCESS (0)", rclcpp::to_string(rclcpp::FutureReturnCode::SUCCESS));
|
||||||
|
EXPECT_EQ(
|
||||||
|
"INTERRUPTED (1)", rclcpp::to_string(rclcpp::FutureReturnCode::INTERRUPTED));
|
||||||
|
EXPECT_EQ(
|
||||||
|
"TIMEOUT (2)", rclcpp::to_string(rclcpp::FutureReturnCode::TIMEOUT));
|
||||||
|
EXPECT_EQ(
|
||||||
|
"Unknown enum value (3)", rclcpp::to_string(rclcpp::FutureReturnCode(3)));
|
||||||
|
EXPECT_EQ(
|
||||||
|
"Unknown enum value (100)", rclcpp::to_string(rclcpp::FutureReturnCode(100)));
|
||||||
|
}
|
|
@ -198,3 +198,12 @@ TEST(TestNodeOptions, copy) {
|
||||||
rcl_arguments_get_count_unparsed(&rcl_options->arguments));
|
rcl_arguments_get_count_unparsed(&rcl_options->arguments));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
TEST(TestNodeOptions, append_parameter_override) {
|
||||||
|
std::vector<std::string> expected_args{"--unknown-flag", "arg"};
|
||||||
|
auto options = rclcpp::NodeOptions().arguments(expected_args).use_global_arguments(false);
|
||||||
|
rclcpp::Parameter parameter("some_parameter", 10);
|
||||||
|
options.append_parameter_override("some_parameter", 10);
|
||||||
|
EXPECT_EQ(1u, options.parameter_overrides().size());
|
||||||
|
EXPECT_EQ(std::string("some_parameter"), options.parameter_overrides()[0].get_name());
|
||||||
|
}
|
||||||
|
|
|
@ -16,6 +16,7 @@
|
||||||
|
|
||||||
#include <algorithm>
|
#include <algorithm>
|
||||||
#include <limits>
|
#include <limits>
|
||||||
|
#include <memory>
|
||||||
#include <stdexcept>
|
#include <stdexcept>
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
@ -32,6 +33,12 @@ protected:
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
TEST_F(TestParameter, construct_destruct) {
|
||||||
|
EXPECT_NO_THROW(std::make_shared<rclcpp::Parameter>().reset());
|
||||||
|
EXPECT_NO_THROW(std::make_shared<rclcpp::Parameter>("some_parameter").reset());
|
||||||
|
EXPECT_NO_THROW(std::make_shared<rclcpp::Parameter>("some_parameter", 10).reset());
|
||||||
|
}
|
||||||
|
|
||||||
TEST_F(TestParameter, not_set_variant) {
|
TEST_F(TestParameter, not_set_variant) {
|
||||||
// Direct instantiation
|
// Direct instantiation
|
||||||
rclcpp::Parameter not_set_variant;
|
rclcpp::Parameter not_set_variant;
|
||||||
|
@ -56,6 +63,10 @@ TEST_F(TestParameter, not_set_variant) {
|
||||||
EXPECT_EQ(
|
EXPECT_EQ(
|
||||||
rclcpp::ParameterType::PARAMETER_NOT_SET,
|
rclcpp::ParameterType::PARAMETER_NOT_SET,
|
||||||
rclcpp::Parameter::from_parameter_msg(not_set_param).get_type());
|
rclcpp::Parameter::from_parameter_msg(not_set_param).get_type());
|
||||||
|
|
||||||
|
EXPECT_THROW(
|
||||||
|
not_set_variant.get_value<int>(),
|
||||||
|
rclcpp::exceptions::InvalidParameterTypeException);
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST_F(TestParameter, bool_variant) {
|
TEST_F(TestParameter, bool_variant) {
|
||||||
|
|
|
@ -19,6 +19,8 @@
|
||||||
|
|
||||||
#include "rclcpp/rclcpp.hpp"
|
#include "rclcpp/rclcpp.hpp"
|
||||||
|
|
||||||
|
#include "../utils/rclcpp_gtest_macros.hpp"
|
||||||
|
|
||||||
#include "rcl_interfaces/msg/parameter_event.hpp"
|
#include "rcl_interfaces/msg/parameter_event.hpp"
|
||||||
|
|
||||||
class TestParameterClient : public ::testing::Test
|
class TestParameterClient : public ::testing::Test
|
||||||
|
@ -159,3 +161,24 @@ TEST_F(TestParameterClient, sync_parameter_event_subscription) {
|
||||||
(void)event_sub;
|
(void)event_sub;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
Coverage for simple get_parameter methods
|
||||||
|
*/
|
||||||
|
TEST_F(TestParameterClient, sync_parameter_get_parameter) {
|
||||||
|
rclcpp::SyncParametersClient client(node);
|
||||||
|
EXPECT_EQ(10, client.get_parameter("not_a_parameter", 10));
|
||||||
|
|
||||||
|
RCLCPP_EXPECT_THROW_EQ(
|
||||||
|
client.get_parameter<int>("not_a_parameter"),
|
||||||
|
std::runtime_error("Parameter 'not_a_parameter' is not set"));
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
Coverage for async waiting/is_ready
|
||||||
|
*/
|
||||||
|
TEST_F(TestParameterClient, sync_parameter_is_ready) {
|
||||||
|
rclcpp::SyncParametersClient client(node);
|
||||||
|
EXPECT_TRUE(client.wait_for_service());
|
||||||
|
EXPECT_TRUE(client.service_is_ready());
|
||||||
|
}
|
||||||
|
|
|
@ -29,6 +29,7 @@ TEST(TestRate, rate_basics) {
|
||||||
|
|
||||||
auto start = std::chrono::system_clock::now();
|
auto start = std::chrono::system_clock::now();
|
||||||
rclcpp::Rate r(period);
|
rclcpp::Rate r(period);
|
||||||
|
EXPECT_EQ(period, r.period());
|
||||||
ASSERT_FALSE(r.is_steady());
|
ASSERT_FALSE(r.is_steady());
|
||||||
ASSERT_TRUE(r.sleep());
|
ASSERT_TRUE(r.sleep());
|
||||||
auto one = std::chrono::system_clock::now();
|
auto one = std::chrono::system_clock::now();
|
||||||
|
@ -68,6 +69,7 @@ TEST(TestRate, wall_rate_basics) {
|
||||||
|
|
||||||
auto start = std::chrono::steady_clock::now();
|
auto start = std::chrono::steady_clock::now();
|
||||||
rclcpp::WallRate r(period);
|
rclcpp::WallRate r(period);
|
||||||
|
EXPECT_EQ(period, r.period());
|
||||||
ASSERT_TRUE(r.is_steady());
|
ASSERT_TRUE(r.is_steady());
|
||||||
ASSERT_TRUE(r.sleep());
|
ASSERT_TRUE(r.sleep());
|
||||||
auto one = std::chrono::steady_clock::now();
|
auto one = std::chrono::steady_clock::now();
|
||||||
|
@ -98,3 +100,22 @@ TEST(TestRate, wall_rate_basics) {
|
||||||
delta = five - four;
|
delta = five - four;
|
||||||
EXPECT_GT(epsilon, delta);
|
EXPECT_GT(epsilon, delta);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
TEST(TestRate, from_double) {
|
||||||
|
{
|
||||||
|
rclcpp::WallRate rate(1.0);
|
||||||
|
EXPECT_EQ(std::chrono::seconds(1), rate.period());
|
||||||
|
}
|
||||||
|
{
|
||||||
|
rclcpp::WallRate rate(2.0);
|
||||||
|
EXPECT_EQ(std::chrono::milliseconds(500), rate.period());
|
||||||
|
}
|
||||||
|
{
|
||||||
|
rclcpp::WallRate rate(0.5);
|
||||||
|
EXPECT_EQ(std::chrono::seconds(2), rate.period());
|
||||||
|
}
|
||||||
|
{
|
||||||
|
rclcpp::WallRate rate(4.0);
|
||||||
|
EXPECT_EQ(std::chrono::milliseconds(250), rate.period());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
|
@ -54,6 +54,7 @@ protected:
|
||||||
this->executor->cancel();
|
this->executor->cancel();
|
||||||
}
|
}
|
||||||
);
|
);
|
||||||
|
EXPECT_TRUE(timer->is_steady());
|
||||||
|
|
||||||
executor->add_node(test_node);
|
executor->add_node(test_node);
|
||||||
// don't start spinning, let the test dictate when
|
// don't start spinning, let the test dictate when
|
||||||
|
@ -191,3 +192,19 @@ TEST_F(TestTimer, test_bad_arguments) {
|
||||||
rclcpp::GenericTimer<void (*)()>(unitialized_clock, 1us, []() {}, context),
|
rclcpp::GenericTimer<void (*)()>(unitialized_clock, 1us, []() {}, context),
|
||||||
rclcpp::exceptions::RCLError);
|
rclcpp::exceptions::RCLError);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
TEST_F(TestTimer, callback_with_timer) {
|
||||||
|
rclcpp::TimerBase * timer_ptr = nullptr;
|
||||||
|
timer = test_node->create_wall_timer(
|
||||||
|
std::chrono::milliseconds(1),
|
||||||
|
[&timer_ptr](rclcpp::TimerBase & timer) {
|
||||||
|
timer_ptr = &timer;
|
||||||
|
});
|
||||||
|
auto start = std::chrono::steady_clock::now();
|
||||||
|
while (nullptr == timer_ptr &&
|
||||||
|
(std::chrono::steady_clock::now() - start) < std::chrono::milliseconds(100))
|
||||||
|
{
|
||||||
|
executor->spin_once(std::chrono::milliseconds(10));
|
||||||
|
}
|
||||||
|
EXPECT_EQ(timer.get(), timer_ptr);
|
||||||
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue