Skip to content
Merged
Show file tree
Hide file tree
Changes from all 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
21 changes: 21 additions & 0 deletions rclcpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,20 @@ rosidl_generate_interfaces(${PROJECT_NAME}_test_msgs
SKIP_INSTALL
)

ament_add_gtest(test_any_service_callback rclcpp/test_any_service_callback.cpp)
if(TARGET test_any_service_callback)
ament_target_dependencies(test_any_service_callback
"test_msgs"
)
target_link_libraries(test_any_service_callback ${PROJECT_NAME})
endif()
ament_add_gtest(test_any_subscription_callback rclcpp/test_any_subscription_callback.cpp)
if(TARGET test_any_subscription_callback)
ament_target_dependencies(test_any_subscription_callback
"test_msgs"
)
target_link_libraries(test_any_subscription_callback ${PROJECT_NAME})
endif()
ament_add_gtest(test_client rclcpp/test_client.cpp)
if(TARGET test_client)
ament_target_dependencies(test_client
Expand All @@ -39,6 +53,13 @@ if(TARGET test_create_timer)
target_link_libraries(test_create_timer ${PROJECT_NAME})
target_include_directories(test_create_timer PRIVATE rclcpp/)
endif()
ament_add_gtest(test_create_subscription rclcpp/test_create_subscription.cpp)
if(TARGET test_create_subscription)
target_link_libraries(test_create_subscription ${PROJECT_NAME})
ament_target_dependencies(test_create_subscription
"test_msgs"
)
endif()
ament_add_gtest(test_expand_topic_or_service_name rclcpp/test_expand_topic_or_service_name.cpp)
if(TARGET test_expand_topic_or_service_name)
ament_target_dependencies(test_expand_topic_or_service_name
Expand Down
78 changes: 78 additions & 0 deletions rclcpp/test/rclcpp/test_any_service_callback.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
// 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.

// This file includes basic API tests for the AnyServiceCallback class.
// It is also tested in test_externally_defined_services.cpp

#include <gtest/gtest.h>

#include <functional>
#include <memory>
#include <utility>

#include "rclcpp/any_service_callback.hpp"
#include "test_msgs/srv/empty.hpp"
#include "test_msgs/srv/empty.h"

class TestAnyServiceCallback : public ::testing::Test
{
public:
void SetUp()
{
request_header_ = std::make_shared<rmw_request_id_t>();
request_ = std::make_shared<test_msgs::srv::Empty::Request>();
response_ = std::make_shared<test_msgs::srv::Empty::Response>();
}

protected:
rclcpp::AnyServiceCallback<test_msgs::srv::Empty> any_service_callback_;
std::shared_ptr<rmw_request_id_t> request_header_;
std::shared_ptr<test_msgs::srv::Empty::Request> request_;
std::shared_ptr<test_msgs::srv::Empty::Response> response_;
};

TEST_F(TestAnyServiceCallback, no_set_and_dispatch_throw) {
EXPECT_THROW(
any_service_callback_.dispatch(request_header_, request_, response_),
std::runtime_error);
}

TEST_F(TestAnyServiceCallback, set_and_dispatch_no_header) {
int callback_calls = 0;
auto callback = [&callback_calls](const std::shared_ptr<test_msgs::srv::Empty::Request>,
std::shared_ptr<test_msgs::srv::Empty::Response>) {
callback_calls++;
};

any_service_callback_.set(callback);
EXPECT_NO_THROW(
any_service_callback_.dispatch(request_header_, request_, response_));
EXPECT_EQ(callback_calls, 1);
}


TEST_F(TestAnyServiceCallback, set_and_dispatch_header) {
int callback_with_header_calls = 0;
auto callback_with_header =
[&callback_with_header_calls](const std::shared_ptr<rmw_request_id_t>,
const std::shared_ptr<test_msgs::srv::Empty::Request>,
std::shared_ptr<test_msgs::srv::Empty::Response>) {
callback_with_header_calls++;
};

any_service_callback_.set(callback_with_header);
EXPECT_NO_THROW(
any_service_callback_.dispatch(request_header_, request_, response_));
EXPECT_EQ(callback_with_header_calls, 1);
}
205 changes: 205 additions & 0 deletions rclcpp/test/rclcpp/test_any_subscription_callback.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,205 @@
// 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 <functional>
#include <memory>
#include <utility>

#include "rclcpp/any_subscription_callback.hpp"
#include "test_msgs/msg/empty.hpp"
#include "test_msgs/msg/empty.h"

class TestAnySubscriptionCallback : public ::testing::Test
{
public:
TestAnySubscriptionCallback()
: any_subscription_callback_(allocator_) {}
void SetUp()
{
msg_shared_ptr_ = std::make_shared<test_msgs::msg::Empty>();
msg_const_shared_ptr_ = std::make_shared<const test_msgs::msg::Empty>();
msg_unique_ptr_ = std::make_unique<test_msgs::msg::Empty>();
}

protected:
std::shared_ptr<std::allocator<void>> allocator_;
rclcpp::AnySubscriptionCallback<test_msgs::msg::Empty, std::allocator<void>>
any_subscription_callback_;

std::shared_ptr<test_msgs::msg::Empty> msg_shared_ptr_;
std::shared_ptr<const test_msgs::msg::Empty> msg_const_shared_ptr_;
std::unique_ptr<test_msgs::msg::Empty> msg_unique_ptr_;
rclcpp::MessageInfo message_info_;
};

TEST_F(TestAnySubscriptionCallback, construct_destruct) {
}

TEST_F(TestAnySubscriptionCallback, unset_dispatch_throw) {
EXPECT_THROW(
any_subscription_callback_.dispatch(msg_shared_ptr_, message_info_),
std::runtime_error);
EXPECT_THROW(
any_subscription_callback_.dispatch_intra_process(msg_const_shared_ptr_, message_info_),
std::runtime_error);
EXPECT_THROW(
any_subscription_callback_.dispatch_intra_process(std::move(msg_unique_ptr_), message_info_),
std::runtime_error);
}

TEST_F(TestAnySubscriptionCallback, set_dispatch_shared_ptr) {
int callback_count = 0;
auto shared_ptr_callback = [&callback_count](
const std::shared_ptr<test_msgs::msg::Empty>) {
callback_count++;
};

any_subscription_callback_.set(shared_ptr_callback);
EXPECT_NO_THROW(any_subscription_callback_.dispatch(msg_shared_ptr_, message_info_));
EXPECT_EQ(callback_count, 1);

// Can't convert ConstSharedPtr to SharedPtr
EXPECT_THROW(
any_subscription_callback_.dispatch_intra_process(msg_const_shared_ptr_, message_info_),
std::runtime_error);
EXPECT_EQ(callback_count, 1);

// Promotes Unique into SharedPtr
EXPECT_NO_THROW(
any_subscription_callback_.dispatch_intra_process(std::move(msg_unique_ptr_), message_info_));
EXPECT_EQ(callback_count, 2);
}

TEST_F(TestAnySubscriptionCallback, set_dispatch_shared_ptr_w_info) {
int callback_count = 0;
auto shared_ptr_w_info_callback = [&callback_count](
const std::shared_ptr<test_msgs::msg::Empty>, const rclcpp::MessageInfo &) {
callback_count++;
};

any_subscription_callback_.set(shared_ptr_w_info_callback);

EXPECT_NO_THROW(any_subscription_callback_.dispatch(msg_shared_ptr_, message_info_));
EXPECT_EQ(callback_count, 1);

// Can't convert ConstSharedPtr to SharedPtr
EXPECT_THROW(
any_subscription_callback_.dispatch_intra_process(msg_const_shared_ptr_, message_info_),
std::runtime_error);
EXPECT_EQ(callback_count, 1);

// Promotes Unique into SharedPtr
EXPECT_NO_THROW(
any_subscription_callback_.dispatch_intra_process(std::move(msg_unique_ptr_), message_info_));
EXPECT_EQ(callback_count, 2);
}

TEST_F(TestAnySubscriptionCallback, set_dispatch_const_shared_ptr) {
int callback_count = 0;
auto const_shared_ptr_callback = [&callback_count](
std::shared_ptr<const test_msgs::msg::Empty>) {
callback_count++;
};

any_subscription_callback_.set(const_shared_ptr_callback);

// Ok to promote shared_ptr to ConstSharedPtr
EXPECT_NO_THROW(any_subscription_callback_.dispatch(msg_shared_ptr_, message_info_));
EXPECT_EQ(callback_count, 1);

EXPECT_NO_THROW(
any_subscription_callback_.dispatch_intra_process(msg_const_shared_ptr_, message_info_));
EXPECT_EQ(callback_count, 2);

// Not allowed to convert unique_ptr to const shared_ptr
EXPECT_THROW(
any_subscription_callback_.dispatch_intra_process(std::move(msg_unique_ptr_), message_info_),
std::runtime_error);
EXPECT_EQ(callback_count, 2);
}

TEST_F(TestAnySubscriptionCallback, set_dispatch_const_shared_ptr_w_info) {
int callback_count = 0;
auto const_shared_ptr_callback = [&callback_count](
std::shared_ptr<const test_msgs::msg::Empty>, const rclcpp::MessageInfo &) {
callback_count++;
};

any_subscription_callback_.set(
std::move(const_shared_ptr_callback));

// Ok to promote shared_ptr to ConstSharedPtr
EXPECT_NO_THROW(any_subscription_callback_.dispatch(msg_shared_ptr_, message_info_));
EXPECT_EQ(callback_count, 1);

EXPECT_NO_THROW(
any_subscription_callback_.dispatch_intra_process(msg_const_shared_ptr_, message_info_));
EXPECT_EQ(callback_count, 2);

// Not allowed to convert unique_ptr to const shared_ptr
EXPECT_THROW(
any_subscription_callback_.dispatch_intra_process(std::move(msg_unique_ptr_), message_info_),
std::runtime_error);
EXPECT_EQ(callback_count, 2);
}

TEST_F(TestAnySubscriptionCallback, set_dispatch_unique_ptr) {
int callback_count = 0;
auto unique_ptr_callback = [&callback_count](
std::unique_ptr<test_msgs::msg::Empty>) {
callback_count++;
};

any_subscription_callback_.set(unique_ptr_callback);

// Message is copied into unique_ptr
EXPECT_NO_THROW(any_subscription_callback_.dispatch(msg_shared_ptr_, message_info_));
EXPECT_EQ(callback_count, 1);

EXPECT_THROW(
any_subscription_callback_.dispatch_intra_process(msg_const_shared_ptr_, message_info_),
std::runtime_error);
EXPECT_EQ(callback_count, 1);

// Unique_ptr is_moved
EXPECT_NO_THROW(
any_subscription_callback_.dispatch_intra_process(std::move(msg_unique_ptr_), message_info_));
EXPECT_EQ(callback_count, 2);
}

TEST_F(TestAnySubscriptionCallback, set_dispatch_unique_ptr_w_info) {
int callback_count = 0;
auto unique_ptr_callback = [&callback_count](
std::unique_ptr<test_msgs::msg::Empty>, const rclcpp::MessageInfo &) {
callback_count++;
};

any_subscription_callback_.set(unique_ptr_callback);

// Message is copied into unique_ptr
EXPECT_NO_THROW(any_subscription_callback_.dispatch(msg_shared_ptr_, message_info_));
EXPECT_EQ(callback_count, 1);

EXPECT_THROW(
any_subscription_callback_.dispatch_intra_process(msg_const_shared_ptr_, message_info_),
std::runtime_error);
EXPECT_EQ(callback_count, 1);

// Unique_ptr is_moved
EXPECT_NO_THROW(
any_subscription_callback_.dispatch_intra_process(std::move(msg_unique_ptr_), message_info_));
EXPECT_EQ(callback_count, 2);
}
67 changes: 67 additions & 0 deletions rclcpp/test/rclcpp/test_create_subscription.cpp
Original file line number Diff line number Diff line change
@@ -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 <chrono>
#include <memory>

#include "rclcpp/create_subscription.hpp"
#include "rclcpp/node.hpp"
#include "test_msgs/msg/empty.hpp"
#include "test_msgs/msg/empty.h"

using namespace std::chrono_literals;

class TestCreateSubscription : public ::testing::Test
{
public:
void SetUp() override
{
rclcpp::init(0, nullptr);
}

void TearDown() override
{
rclcpp::shutdown();
}
};

TEST_F(TestCreateSubscription, create) {
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns");
const rclcpp::QoS qos(10);
auto options = rclcpp::SubscriptionOptions();
auto callback = [](const test_msgs::msg::Empty::SharedPtr) {};
auto subscription =
rclcpp::create_subscription<test_msgs::msg::Empty>(node, "topic_name", qos, callback, options);

ASSERT_NE(nullptr, subscription);
EXPECT_STREQ("/ns/topic_name", subscription->get_topic_name());
}

TEST_F(TestCreateSubscription, create_with_statistics) {
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns");
const rclcpp::QoS qos(10);
auto options = rclcpp::SubscriptionOptions();
options.topic_stats_options.state = rclcpp::TopicStatisticsState::Enable;
options.topic_stats_options.publish_topic = "topic_statistics";
options.topic_stats_options.publish_period = 5min;

auto callback = [](const test_msgs::msg::Empty::SharedPtr) {};
auto subscription =
rclcpp::create_subscription<test_msgs::msg::Empty>(node, "topic_name", qos, callback, options);

ASSERT_NE(nullptr, subscription);
EXPECT_STREQ("/ns/topic_name", subscription->get_topic_name());
}