Skip to content
Merged
Show file tree
Hide file tree
Changes from 5 commits
Commits
Show all changes
38 commits
Select commit Hold shift + click to select a range
c68112c
refactor + tests
ivanpauno Oct 15, 2020
5a1c5c7
Update create_publisher, and others ...
ivanpauno Oct 15, 2020
472a1bd
Add QosOverridingOptions to create_subscription
ivanpauno Oct 15, 2020
dc1b075
linters
ivanpauno Oct 15, 2020
6440680
Use new rmw functions
ivanpauno Oct 20, 2020
6d21d39
Simplify code
ivanpauno Oct 20, 2020
ffd4659
Add overloads to create_publisher/create_subscription taking both a p…
ivanpauno Oct 20, 2020
95068b5
Make use of qos overrides in some default topics
ivanpauno Oct 21, 2020
730c741
Please linters, add more notes
ivanpauno Oct 21, 2020
875c721
use resolved topic name
ivanpauno Oct 21, 2020
aafadb3
Modify macro name
ivanpauno Oct 22, 2020
0cb162a
Rename qpk to policy
ivanpauno Oct 22, 2020
fa10924
reorder headers
ivanpauno Oct 22, 2020
58fcecf
Fix bugs, add tests
ivanpauno Oct 22, 2020
2424238
Tests for new create_publisher/create_subscription overloads
ivanpauno Oct 23, 2020
5fdcb04
don't make /clock reconfigurable
ivanpauno Oct 23, 2020
4d83c8b
Add tests for validation callback, cleanup QosOverridingOptions api
ivanpauno Oct 23, 2020
3c5b855
Undo unneeded changes
ivanpauno Oct 23, 2020
5465266
Remove comment
ivanpauno Oct 30, 2020
5507be4
Write docs for QosOverridingOptions
ivanpauno Oct 30, 2020
091b6a2
style
ivanpauno Oct 30, 2020
4121a6b
style
ivanpauno Oct 30, 2020
ea604e7
style
ivanpauno Oct 30, 2020
aa5ff31
style
ivanpauno Oct 30, 2020
1d168dd
style
ivanpauno Oct 30, 2020
927461a
style
ivanpauno Oct 30, 2020
dd92127
Use declare parameter or get
ivanpauno Nov 5, 2020
96ea51a
Improve tests
ivanpauno Nov 5, 2020
a36a219
Remove rclcpp/test/detail folder
ivanpauno Nov 5, 2020
e7355f7
Use Duration::from_nanoseconds
ivanpauno Nov 5, 2020
22a5412
Modify the qos validation callback signature so a reason of while the…
ivanpauno Nov 6, 2020
71578d2
100% line coverage in rclcpp/detail/qos_parameters.hpp
ivanpauno Nov 13, 2020
17c136f
100% coverage in create_publisher.hpp/create_subscription.hpp
ivanpauno Nov 13, 2020
f65e971
100% coverage in test_qos_overriding_options.cpp
ivanpauno Nov 13, 2020
3ee91e6
Delete unnecessary includes
ivanpauno Nov 13, 2020
b9d7102
Delete unnecesary test, please linters
ivanpauno Nov 13, 2020
04398a4
Uncomment line
ivanpauno Nov 16, 2020
da07423
Delete unneeded include
ivanpauno Nov 16, 2020
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
8 changes: 4 additions & 4 deletions rclcpp/include/rclcpp/detail/qos_parameters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,9 +195,9 @@ declare_qos_parameters(
EntityQosParametersTraits)
{
if (options.policy_kinds.size()) {
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"qos override options ignored because no parameter interface was provided");
std::runtime_error exc{
"passed non-default qos overriding options without providing a parameters interface"};
throw exc;
}
return default_qos;
}
Expand Down Expand Up @@ -252,7 +252,7 @@ apply_qos_override(
reliability, RELIABILITY, value, qos);
break;
default:
throw std::runtime_error{"unknown QosPolicyKind"};
throw std::invalid_argument{"unknown QosPolicyKind"};
}
}

Expand Down
2 changes: 0 additions & 2 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@
#include "rclcpp/client.hpp"
#include "rclcpp/clock.hpp"
#include "rclcpp/context.hpp"
#include "rclcpp/detail/qos_parameters.hpp"
#include "rclcpp/event.hpp"
#include "rclcpp/logger.hpp"
#include "rclcpp/macros.hpp"
Expand All @@ -60,7 +59,6 @@
#include "rclcpp/publisher.hpp"
#include "rclcpp/publisher_options.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/qos_overriding_options.hpp"
#include "rclcpp/service.hpp"
#include "rclcpp/subscription.hpp"
#include "rclcpp/subscription_options.hpp"
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ find_package(test_msgs REQUIRED)

include(cmake/rclcpp_add_build_failure_test.cmake)

add_subdirectory(benchmark)
# add_subdirectory(benchmark)
add_subdirectory(rclcpp)

ament_add_gtest(test_rclcpp_gtest_macros utils/test_rclcpp_gtest_macros.cpp)
Expand Down
6 changes: 6 additions & 0 deletions rclcpp/test/rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -369,6 +369,12 @@ if(TARGET test_qos_event)
mimick
)
endif()
ament_add_gmock(test_qos_overriding_options test_qos_overriding_options.cpp)
if(TARGET test_qos_overriding_options)
target_link_libraries(test_qos_overriding_options
${PROJECT_NAME}
)
endif()
ament_add_gmock(test_qos_parameters test_qos_parameters.cpp)
if(TARGET test_qos_parameters)
target_link_libraries(test_qos_parameters
Expand Down
15 changes: 15 additions & 0 deletions rclcpp/test/rclcpp/test_create_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include <chrono>
#include <memory>
#include <utility>

#include "rclcpp/create_subscription.hpp"
#include "rclcpp/node.hpp"
Expand Down Expand Up @@ -50,6 +51,20 @@ TEST_F(TestCreateSubscription, create) {
EXPECT_STREQ("/ns/topic_name", subscription->get_topic_name());
}

TEST_F(TestCreateSubscription, create_with_overriding_options) {
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns");
const rclcpp::QoS qos(10);
auto options = rclcpp::SubscriptionOptions();
options.qos_overriding_options = rclcpp::QosOverridingOptions{
rclcpp::QosOverridingOptions::kDefaultPolicies};
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_separated_node_topics_and_parameters) {
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns");
const rclcpp::QoS qos(10);
Expand Down
8 changes: 8 additions & 0 deletions rclcpp/test/rclcpp/test_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,6 +151,14 @@ TEST_F(TestPublisher, various_creation_signatures) {
rclcpp::create_publisher<Empty>(node, "topic", 42, rclcpp::PublisherOptions());
(void)publisher;
}
{
rclcpp::PublisherOptions options;
options.qos_overriding_options = rclcpp::QosOverridingOptions{
rclcpp::QosOverridingOptions::kDefaultPolicies};
auto publisher =
rclcpp::create_publisher<Empty>(node, "topic", 42, options);
(void)publisher;
}
{
auto node_parameters = node->get_node_parameters_interface();
auto node_topics = node->get_node_topics_interface();
Expand Down
34 changes: 34 additions & 0 deletions rclcpp/test/rclcpp/test_qos_overriding_options.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
// 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 "gmock/gmock.h"

#include "rclcpp/qos_overriding_options.hpp"

TEST(TestQosOverridingOptions, test_overriding_options) {
rclcpp::QosOverridingOptions options{rclcpp::QosOverridingOptions::kDefaultPolicies};
EXPECT_EQ(options.id, "");
EXPECT_EQ(options.validation_callback, nullptr);
EXPECT_THAT(
options.policy_kinds, testing::ElementsAre(
rclcpp::QosPolicyKind::History,
rclcpp::QosPolicyKind::Depth,
rclcpp::QosPolicyKind::Reliability));
}

TEST(TestQosOverridingOptions, test_qos_policy_kind_to_cstr) {
EXPECT_THROW(
rclcpp::qos_policy_kind_to_cstr(rclcpp::QosPolicyKind::Invalid),
std::invalid_argument);
}
161 changes: 147 additions & 14 deletions rclcpp/test/rclcpp/test_qos_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,19 +22,6 @@
#include "rclcpp/qos_overriding_options.hpp"
#include "rclcpp/detail/qos_parameters.hpp"

TEST(TestQosParameters, test_overriding_options) {
{
rclcpp::QosOverridingOptions options{rclcpp::QosOverridingOptions::kDefaultPolicies};
EXPECT_EQ(options.id, "");
EXPECT_EQ(options.validation_callback, nullptr);
EXPECT_THAT(
options.policy_kinds, testing::ElementsAre(
rclcpp::QosPolicyKind::History,
rclcpp::QosPolicyKind::Depth,
rclcpp::QosPolicyKind::Reliability));
}
}

TEST(TestQosParameters, declare) {
rclcpp::init(0, nullptr);
auto node = std::make_shared<rclcpp::Node>(
Expand Down Expand Up @@ -96,7 +83,7 @@ TEST(TestQosParameters, declare_with_callback) {
EXPECT_THROW(
rclcpp::detail::declare_qos_parameters(
{
rclcpp::QosOverridingOptions::kDefaultPolicies,
{rclcpp::QosPolicyKind::Lifespan},
[](const rclcpp::QoS &) {
return rclcpp::QosCallbackResult{};
}
Expand Down Expand Up @@ -124,3 +111,149 @@ TEST(TestQosParameters, declare_with_callback) {

rclcpp::shutdown();
}

constexpr int64_t kDuration{1000000};

TEST(TestQosParameters, declare_qos_subscription_parameters) {
rclcpp::init(0, nullptr);
auto node = std::make_shared<rclcpp::Node>(
"my_node", "/ns", rclcpp::NodeOptions().parameter_overrides(
{
rclcpp::Parameter(
"qos_overrides./my/fully/qualified/topic_name.subscription.reliability", "best_effort"),
rclcpp::Parameter(
"qos_overrides./my/fully/qualified/topic_name.subscription.deadline", kDuration),
rclcpp::Parameter(
"qos_overrides./my/fully/qualified/topic_name.subscription.liveliness_lease_duration",
kDuration),
}));

for (size_t i = 0; i < 2; ++i) {
// The first iteration will declare parameters, the second will get the previosuly declared
// ones, check both have the same result.
rclcpp::QoS qos{rclcpp::KeepLast(10)};
qos = rclcpp::detail::declare_qos_parameters(
{
rclcpp::QosPolicyKind::AvoidRosNamespaceConventions, rclcpp::QosPolicyKind::Deadline,
rclcpp::QosPolicyKind::Depth, rclcpp::QosPolicyKind::Durability,
// lifespan will be ignored
rclcpp::QosPolicyKind::History, rclcpp::QosPolicyKind::Lifespan,
rclcpp::QosPolicyKind::Liveliness, rclcpp::QosPolicyKind::LivelinessLeaseDuration,
rclcpp::QosPolicyKind::Reliability
},
node,
"/my/fully/qualified/topic_name",
qos,
rclcpp::detail::SubscriptionQosParametersTraits{});

EXPECT_EQ(
node->get_parameter(
"qos_overrides./my/fully/qualified/topic_name.subscription.avoid_ros_namespace_conventions"
).get_value<bool>(), false);
EXPECT_EQ(
node->get_parameter(
"qos_overrides./my/fully/qualified/topic_name.subscription.deadline"
).get_value<int64_t>(), kDuration);
EXPECT_EQ(
node->get_parameter(
"qos_overrides./my/fully/qualified/topic_name.subscription.depth"
).get_value<int64_t>(), 10);
EXPECT_EQ(
node->get_parameter(
"qos_overrides./my/fully/qualified/topic_name.subscription.durability"
).get_value<std::string>(), "volatile");
EXPECT_EQ(
node->get_parameter(
"qos_overrides./my/fully/qualified/topic_name.subscription.history"
).get_value<std::string>(), "keep_last");
EXPECT_FALSE(
node->has_parameter(
"qos_overrides./my/fully/qualified/topic_name.subscription.lifespan"));
EXPECT_EQ(
node->get_parameter(
"qos_overrides./my/fully/qualified/topic_name.subscription.liveliness"
).get_value<std::string>(), "system_default");
EXPECT_EQ(
node->get_parameter(
"qos_overrides./my/fully/qualified/topic_name.subscription.liveliness_lease_duration"
).get_value<int64_t>(), kDuration);
EXPECT_EQ(
node->get_parameter(
"qos_overrides./my/fully/qualified/topic_name.subscription.reliability"
).get_value<std::string>(),
"best_effort");

std::map<std::string, rclcpp::Parameter> qos_params;
EXPECT_TRUE(
node->get_node_parameters_interface()->get_parameters_by_prefix(
"qos_overrides./my/fully/qualified/topic_name.subscription", qos_params));
EXPECT_EQ(8u, qos_params.size());
}
rclcpp::shutdown();
}

TEST(TestQosParameters, declare_with_id) {
rclcpp::init(0, nullptr);
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns");

rclcpp::QoS qos{rclcpp::KeepLast{10}};
qos = rclcpp::detail::declare_qos_parameters(
{rclcpp::QosOverridingOptions::kDefaultPolicies, nullptr, "my_id"},
node,
"/my/fully/qualified/topic_name",
qos,
rclcpp::detail::PublisherQosParametersTraits{});

std::map<std::string, rclcpp::Parameter> qos_params;
EXPECT_TRUE(
node->get_node_parameters_interface()->get_parameters_by_prefix(
"qos_overrides./my/fully/qualified/topic_name.publisher_my_id", qos_params));
EXPECT_EQ(3u, qos_params.size());

rclcpp::shutdown();
}

TEST(TestQosParameters, declare_no_parameters_interface) {
rclcpp::init(0, nullptr);
auto node = std::make_shared<rclcpp::Node>("my_node", "/ns");

rclcpp::QoS qos{rclcpp::KeepLast{10}};
auto node_base_interface = node->get_node_base_interface();
EXPECT_THROW(
rclcpp::detail::declare_qos_parameters(
rclcpp::QosOverridingOptions::kDefaultPolicies,
node_base_interface,
"/my/fully/qualified/topic_name",
qos,
rclcpp::detail::PublisherQosParametersTraits{}),
std::runtime_error);

qos = rclcpp::detail::declare_qos_parameters(
rclcpp::QosOverridingOptions{},
node_base_interface,
"/my/fully/qualified/topic_name",
qos,
rclcpp::detail::PublisherQosParametersTraits{});

std::map<std::string, rclcpp::Parameter> qos_params;
EXPECT_FALSE(
node->get_node_parameters_interface()->get_parameters_by_prefix("qos_overrides", qos_params));

rclcpp::shutdown();
}

TEST(TestQosParameters, internal_functions_failure_modes) {
rclcpp::QoS qos{rclcpp::KeepLast{10}};
EXPECT_THROW(
rclcpp::detail::apply_qos_override(
rclcpp::QosPolicyKind::Invalid, rclcpp::ParameterValue{}, qos),
std::invalid_argument);
EXPECT_THROW(
rclcpp::detail::get_default_qos_param_value(
rclcpp::QosPolicyKind::Invalid, qos),
std::invalid_argument);
EXPECT_THROW(
rclcpp::detail::check_if_stringified_policy_is_null(
nullptr, rclcpp::QosPolicyKind::Reliability),
std::invalid_argument);
}