Created on_parameter_event
static function (#688)
* created static functions Signed-off-by: alsora <alberto.soragna@gmail.com> Signed-off-by: alberto soragna <alberto.soragna@gmail.com> * updated on_parameter_event to new subscriber api Signed-off-by: alberto soragna <alberto.soragna@gmail.com> * Update parameter_client.hpp Reorderd typenames in template Signed-off-by: alberto soragna <alberto.soragna@gmail.com> * updated API also for Synchronous client and fixed linter errors Signed-off-by: alberto soragna <alberto.soragna@gmail.com> * added empty line at the end of files Signed-off-by: alberto soragna <alberto.soragna@gmail.com> * fixed linter error Signed-off-by: alsora <alberto.soragna@gmail.com> * added parameter client tests Signed-off-by: alsora <alberto.soragna@gmail.com> * added missing includes in unit test Signed-off-by: alsora <alberto.soragna@gmail.com>
This commit is contained in:
parent
2152e0574b
commit
0682ceb3e1
4 changed files with 212 additions and 10 deletions
|
@ -242,6 +242,13 @@ if(BUILD_TESTING)
|
|||
)
|
||||
target_link_libraries(test_node_global_args ${PROJECT_NAME})
|
||||
endif()
|
||||
ament_add_gtest(test_parameter_client test/test_parameter_client.cpp)
|
||||
if(TARGET test_parameter_client)
|
||||
ament_target_dependencies(test_parameter_client
|
||||
"rcl_interfaces"
|
||||
)
|
||||
target_link_libraries(test_parameter_client ${PROJECT_NAME})
|
||||
endif()
|
||||
ament_add_gtest(test_parameter_events_filter test/test_parameter_events_filter.cpp)
|
||||
if(TARGET test_parameter_events_filter)
|
||||
ament_target_dependencies(test_parameter_events_filter
|
||||
|
|
|
@ -121,8 +121,35 @@ public:
|
|||
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
|
||||
))
|
||||
{
|
||||
return rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
|
||||
return this->on_parameter_event(
|
||||
this->node_topics_interface_,
|
||||
callback,
|
||||
qos,
|
||||
options);
|
||||
}
|
||||
|
||||
/**
|
||||
* The NodeT type only needs to have a method called get_node_topics_interface()
|
||||
* which returns a shared_ptr to a NodeTopicsInterface, or be a
|
||||
* NodeTopicsInterface pointer itself.
|
||||
*/
|
||||
template<
|
||||
typename CallbackT,
|
||||
typename NodeT,
|
||||
typename AllocatorT = std::allocator<void>>
|
||||
static typename rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
|
||||
on_parameter_event(
|
||||
NodeT && node,
|
||||
CallbackT && callback,
|
||||
const rclcpp::QoS & qos = (
|
||||
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default))
|
||||
),
|
||||
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
|
||||
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
|
||||
))
|
||||
{
|
||||
return rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
|
||||
node,
|
||||
"parameter_events",
|
||||
qos,
|
||||
std::forward<CallbackT>(callback),
|
||||
|
@ -266,7 +293,26 @@ public:
|
|||
typename rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
|
||||
on_parameter_event(CallbackT && callback)
|
||||
{
|
||||
return async_parameters_client_->on_parameter_event(std::forward<CallbackT>(callback));
|
||||
return async_parameters_client_->on_parameter_event(
|
||||
std::forward<CallbackT>(callback));
|
||||
}
|
||||
|
||||
/**
|
||||
* The NodeT type only needs to have a method called get_node_topics_interface()
|
||||
* which returns a shared_ptr to a NodeTopicsInterface, or be a
|
||||
* NodeTopicsInterface pointer itself.
|
||||
*/
|
||||
template<
|
||||
typename CallbackT,
|
||||
typename NodeT>
|
||||
static typename rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
|
||||
on_parameter_event(
|
||||
NodeT && node,
|
||||
CallbackT && callback)
|
||||
{
|
||||
return AsyncParametersClient::on_parameter_event(
|
||||
node,
|
||||
std::forward<CallbackT>(callback));
|
||||
}
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
|
|
|
@ -103,15 +103,9 @@ void TimeSource::attachNode(
|
|||
}
|
||||
|
||||
// TODO(tfoote) use parameters interface not subscribe to events via topic ticketed #609
|
||||
parameter_client_ = std::make_shared<rclcpp::AsyncParametersClient>(
|
||||
node_base_,
|
||||
parameter_subscription_ = rclcpp::AsyncParametersClient::on_parameter_event(
|
||||
node_topics_,
|
||||
node_graph_,
|
||||
node_services_
|
||||
);
|
||||
parameter_subscription_ =
|
||||
parameter_client_->on_parameter_event(std::bind(&TimeSource::on_parameter_event,
|
||||
this, std::placeholders::_1));
|
||||
std::bind(&TimeSource::on_parameter_event, this, std::placeholders::_1));
|
||||
}
|
||||
|
||||
void TimeSource::detachNode()
|
||||
|
|
155
rclcpp/test/test_parameter_client.cpp
Normal file
155
rclcpp/test/test_parameter_client.cpp
Normal file
|
@ -0,0 +1,155 @@
|
|||
// Copyright 2019 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 <memory>
|
||||
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
|
||||
#include "rcl_interfaces/msg/parameter_event.hpp"
|
||||
|
||||
class TestParameterClient : public ::testing::Test
|
||||
{
|
||||
public:
|
||||
void OnMessage(const rcl_interfaces::msg::ParameterEvent::SharedPtr event)
|
||||
{
|
||||
(void)event;
|
||||
}
|
||||
|
||||
protected:
|
||||
static void SetUpTestCase()
|
||||
{
|
||||
rclcpp::init(0, nullptr);
|
||||
}
|
||||
|
||||
void SetUp()
|
||||
{
|
||||
node = std::make_shared<rclcpp::Node>("test_parameter_client", "/ns");
|
||||
}
|
||||
|
||||
void TearDown()
|
||||
{
|
||||
node.reset();
|
||||
}
|
||||
|
||||
rclcpp::Node::SharedPtr node;
|
||||
};
|
||||
|
||||
/*
|
||||
Testing async parameter client construction and destruction.
|
||||
*/
|
||||
TEST_F(TestParameterClient, async_construction_and_destruction) {
|
||||
{
|
||||
auto asynchronous_client = std::make_shared<rclcpp::AsyncParametersClient>(node);
|
||||
(void)asynchronous_client;
|
||||
}
|
||||
|
||||
{
|
||||
auto asynchronous_client = std::make_shared<rclcpp::AsyncParametersClient>(
|
||||
node->get_node_base_interface(),
|
||||
node->get_node_topics_interface(),
|
||||
node->get_node_graph_interface(),
|
||||
node->get_node_services_interface());
|
||||
(void)asynchronous_client;
|
||||
}
|
||||
|
||||
{
|
||||
ASSERT_THROW({
|
||||
std::make_shared<rclcpp::AsyncParametersClient>(node, "invalid_remote_node?");
|
||||
}, rclcpp::exceptions::InvalidServiceNameError);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
Testing sync parameter client construction and destruction.
|
||||
*/
|
||||
TEST_F(TestParameterClient, sync_construction_and_destruction) {
|
||||
{
|
||||
auto synchronous_client = std::make_shared<rclcpp::SyncParametersClient>(node);
|
||||
(void)synchronous_client;
|
||||
}
|
||||
|
||||
{
|
||||
auto synchronous_client = std::make_shared<rclcpp::SyncParametersClient>(
|
||||
std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
|
||||
node);
|
||||
(void)synchronous_client;
|
||||
}
|
||||
|
||||
{
|
||||
auto synchronous_client = std::make_shared<rclcpp::SyncParametersClient>(
|
||||
std::make_shared<rclcpp::executors::SingleThreadedExecutor>(),
|
||||
node->get_node_base_interface(),
|
||||
node->get_node_topics_interface(),
|
||||
node->get_node_graph_interface(),
|
||||
node->get_node_services_interface());
|
||||
(void)synchronous_client;
|
||||
}
|
||||
|
||||
{
|
||||
ASSERT_THROW({
|
||||
std::make_shared<rclcpp::SyncParametersClient>(node, "invalid_remote_node?");
|
||||
}, rclcpp::exceptions::InvalidServiceNameError);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
Testing different methods for parameter event subscription from asynchronous clients.
|
||||
*/
|
||||
TEST_F(TestParameterClient, async_parameter_event_subscription) {
|
||||
auto callback = std::bind(&TestParameterClient::OnMessage, this, std::placeholders::_1);
|
||||
{
|
||||
auto asynchronous_client = std::make_shared<rclcpp::AsyncParametersClient>(node);
|
||||
auto event_sub = asynchronous_client->on_parameter_event(callback);
|
||||
(void)event_sub;
|
||||
}
|
||||
|
||||
{
|
||||
auto event_sub = rclcpp::AsyncParametersClient::on_parameter_event(node, callback);
|
||||
(void)event_sub;
|
||||
}
|
||||
|
||||
{
|
||||
auto event_sub = rclcpp::AsyncParametersClient::on_parameter_event(
|
||||
node->get_node_topics_interface(),
|
||||
callback);
|
||||
(void)event_sub;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
Testing different methods for parameter event subscription from synchronous clients.
|
||||
*/
|
||||
TEST_F(TestParameterClient, sync_parameter_event_subscription) {
|
||||
auto callback = std::bind(&TestParameterClient::OnMessage, this, std::placeholders::_1);
|
||||
{
|
||||
auto synchronous_client = std::make_shared<rclcpp::SyncParametersClient>(node);
|
||||
auto event_sub = synchronous_client->on_parameter_event(callback);
|
||||
(void)event_sub;
|
||||
}
|
||||
|
||||
{
|
||||
auto event_sub = rclcpp::SyncParametersClient::on_parameter_event(node, callback);
|
||||
(void)event_sub;
|
||||
}
|
||||
|
||||
{
|
||||
auto event_sub = rclcpp::SyncParametersClient::on_parameter_event(
|
||||
node->get_node_topics_interface(),
|
||||
callback);
|
||||
(void)event_sub;
|
||||
}
|
||||
}
|
Loading…
Add table
Add a link
Reference in a new issue