Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add coverage for missing API (except executors) #1326

Merged
merged 3 commits into from
Sep 23, 2020
Merged
Show file tree
Hide file tree
Changes from 2 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
25 changes: 25 additions & 0 deletions rclcpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,25 @@ rosidl_generate_interfaces(${PROJECT_NAME}_test_msgs
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
# TODO(brawner) remove when destroying Node for Connext is resolved. See:
# https://github.com/ros2/rclcpp/issues/1250
Expand Down Expand Up @@ -109,6 +128,12 @@ if(TARGET test_function_traits)
"rosidl_typesupport_cpp"
)
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)
if(TARGET test_intra_process_manager)
ament_target_dependencies(test_intra_process_manager
Expand Down
65 changes: 65 additions & 0 deletions rclcpp/test/rclcpp/allocator/test_allocator_common.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
// 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.state);
}

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_EQ(nullptr, rcl_allocator.state);
}
101 changes: 101 additions & 0 deletions rclcpp/test/rclcpp/allocator/test_allocator_deleter.cpp
Original file line number Diff line number Diff line change
@@ -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);

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe add an ASSERT_NE(nullptr, some_mem); ?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done

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(),
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@brawner out of curiosity, why using lambdas instead of putting the block statement right in here?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

My compiler was having trouble parsing the templated function inside a macro.

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 changes: 58 additions & 0 deletions rclcpp/test/rclcpp/exceptions/test_exceptions.cpp
Original file line number Diff line number Diff line change
@@ -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);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I forget how the mocking works; do we need to "unmock" after this, or does leaving the scope do that?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The scope block takes care of that, which is awesome

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 changes: 34 additions & 0 deletions rclcpp/test/rclcpp/test_future_return_code.cpp
Original file line number Diff line number Diff line change
@@ -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)));
}
9 changes: 9 additions & 0 deletions rclcpp/test/rclcpp/test_node_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -198,3 +198,12 @@ TEST(TestNodeOptions, copy) {
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());
}
11 changes: 11 additions & 0 deletions rclcpp/test/rclcpp/test_parameter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include <algorithm>
#include <limits>
#include <memory>
#include <stdexcept>
#include <string>
#include <vector>
Expand All @@ -32,6 +33,12 @@ class TestParameter : public ::testing::Test
}
};

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) {
// Direct instantiation
rclcpp::Parameter not_set_variant;
Expand All @@ -56,6 +63,10 @@ TEST_F(TestParameter, not_set_variant) {
EXPECT_EQ(
rclcpp::ParameterType::PARAMETER_NOT_SET,
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) {
Expand Down
23 changes: 23 additions & 0 deletions rclcpp/test/rclcpp/test_parameter_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@

#include "rclcpp/rclcpp.hpp"

#include "../utils/rclcpp_gtest_macros.hpp"

#include "rcl_interfaces/msg/parameter_event.hpp"

class TestParameterClient : public ::testing::Test
Expand Down Expand Up @@ -159,3 +161,24 @@ TEST_F(TestParameterClient, sync_parameter_event_subscription) {
(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());
hidmic marked this conversation as resolved.
Show resolved Hide resolved
}
Loading