Skip to content

Commit

Permalink
Increasing test coverage of rclcpp_action
Browse files Browse the repository at this point in the history
Signed-off-by: Stephen Brawner <brawner@gmail.com>
  • Loading branch information
brawner committed Mar 31, 2020
1 parent 9017efb commit 91dedaf
Show file tree
Hide file tree
Showing 4 changed files with 113 additions and 0 deletions.
10 changes: 10 additions & 0 deletions rclcpp_action/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,16 @@ if(BUILD_TESTING)
${PROJECT_NAME}
)
endif()

ament_add_gtest(test_types test/test_types.cpp)
if(TARGET test_types)
ament_target_dependencies(test_types
"test_msgs"
)
target_link_libraries(test_types
${PROJECT_NAME}
)
endif()
endif()

ament_package()
15 changes: 15 additions & 0 deletions rclcpp_action/test/test_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -270,6 +270,21 @@ TEST_F(TestClient, construction_and_destruction)
ASSERT_NO_THROW(rclcpp_action::create_client<ActionType>(client_node, action_name).reset());
}

TEST_F(TestClient, construction_and_destruction_callback_group)
{
auto group = client_node->create_callback_group(
rclcpp::callback_group::CallbackGroupType::MutuallyExclusive);
ASSERT_NO_THROW(
rclcpp_action::create_client<ActionType>(
client_node->get_node_base_interface(),
client_node->get_node_graph_interface(),
client_node->get_node_logging_interface(),
client_node->get_node_waitables_interface(),
action_name,
group
).reset());
}

TEST_F(TestClient, async_send_goal_no_callbacks)
{
auto action_client = rclcpp_action::create_client<ActionType>(client_node, action_name);
Expand Down
26 changes: 26 additions & 0 deletions rclcpp_action/test/test_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,32 @@ TEST_F(TestServer, construction_and_destruction)
(void)as;
}

TEST_F(TestServer, construction_and_destruction_callback_group)
{
auto node = std::make_shared<rclcpp::Node>("construct_node", "/rclcpp_action/construct");
auto group = node->create_callback_group(
rclcpp::callback_group::CallbackGroupType::MutuallyExclusive);
const rcl_action_server_options_t & options = rcl_action_server_get_default_options();

using GoalHandle = rclcpp_action::ServerGoalHandle<Fibonacci>;
auto as = rclcpp_action::create_server<Fibonacci>(
node->get_node_base_interface(),
node->get_node_clock_interface(),
node->get_node_logging_interface(),
node->get_node_waitables_interface(),
"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>) {},
options,
group);
(void)as;
}

TEST_F(TestServer, handle_goal_called)
{
auto node = std::make_shared<rclcpp::Node>("handle_goal_node", "/rclcpp_action/handle_goal");
Expand Down
62 changes: 62 additions & 0 deletions rclcpp_action/test/test_types.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
// 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 <limits>
#include "rclcpp_action/types.hpp"

TEST(TestActionTypes, goal_uuid_to_string) {
rclcpp_action::GoalUUID goal_id;
for (size_t i = 0; i < UUID_SIZE; ++i) {
goal_id[i] = i;
}
EXPECT_STREQ("0123456789abcdef", rclcpp_action::to_string(goal_id).c_str());

for (size_t i = 0; i < UUID_SIZE; ++i) {
goal_id[i] = 16u + i;
}
EXPECT_STREQ("101112131415161718191a1b1c1d1e1f", rclcpp_action::to_string(goal_id).c_str());

for (size_t i = 0; i < UUID_SIZE; ++i) {
goal_id[i] = std::numeric_limits<uint8_t>::max() - i;
}
EXPECT_STREQ("fffefdfcfbfaf9f8f7f6f5f4f3f2f1f0", rclcpp_action::to_string(goal_id).c_str());
}

TEST(TestActionTypes, goal_uuid_to_rcl_action_goal_info) {
rclcpp_action::GoalUUID goal_id;
for (size_t i = 0; i < UUID_SIZE; ++i) {
goal_id[i] = i;
}
rcl_action_goal_info_t goal_info = rcl_action_get_zero_initialized_goal_info();
rclcpp_action::convert(goal_id, &goal_info);
for (size_t i = 0; i < UUID_SIZE; ++i) {
EXPECT_EQ(goal_info.goal_id.uuid[i], goal_id[i]);
}
}

TEST(TestActionTypes, rcl_action_goal_info_to_goal_uuid) {
rcl_action_goal_info_t goal_info = rcl_action_get_zero_initialized_goal_info();
for (size_t i = 0; i < UUID_SIZE; ++i) {
goal_info.goal_id.uuid[i] = i;
}

rclcpp_action::GoalUUID goal_id;
rclcpp_action::convert(goal_id, &goal_info);
for (size_t i = 0; i < UUID_SIZE; ++i) {
EXPECT_EQ(goal_info.goal_id.uuid[i], goal_id[i]);
}
}

0 comments on commit 91dedaf

Please sign in to comment.