change API to encourage users to specify history depth always (#713)
* improve interoperability with rclcpp::Duration and std::chrono Signed-off-by: William Woodall <william@osrfoundation.org> * add to_rmw_time to Duration Signed-off-by: William Woodall <william@osrfoundation.org> * add new QoS class to rclcpp Signed-off-by: William Woodall <william@osrfoundation.org> * changes to NodeBase, NodeTopics, etc in preparation for changes to pub/sub Signed-off-by: William Woodall <william@osrfoundation.org> * refactor publisher creation to use new QoS class Signed-off-by: William Woodall <william@osrfoundation.org> * refactor subscription creation to use new QoS class Signed-off-by: William Woodall <william@osrfoundation.org> * fixing fallout from changes to pub/sub creation Signed-off-by: William Woodall <william@osrfoundation.org> * fixed Windows error: no appropriate default constructor available why? who knows Signed-off-by: William Woodall <william@osrfoundation.org> * fixed Windows error: could not deduce template argument for 'PublisherT' Signed-off-by: William Woodall <william@osrfoundation.org> * fix missing vftable linker error on Windows Signed-off-by: William Woodall <william@osrfoundation.org> * fix more cases of no suitable default constructor errors... Signed-off-by: William Woodall <william@osrfoundation.org> * prevent msvc from trying to interpret some cases as functions Signed-off-by: William Woodall <william@osrfoundation.org> * uncrustify Signed-off-by: William Woodall <william@osrfoundation.org> * cpplint Signed-off-by: William Woodall <william@osrfoundation.org> * add C++ version of default action qos Signed-off-by: William Woodall <william@osrfoundation.org> * fixing lifecycle subscription signatures Signed-off-by: William Woodall <william@osrfoundation.org> * fix allocators (we actually use this already in the pub/sub factory) Signed-off-by: William Woodall <william@osrfoundation.org> * suppress cppcheck on false positive syntax error Signed-off-by: William Woodall <william@osrfoundation.org> * fix more cppcheck syntax error false positives Signed-off-by: William Woodall <william@osrfoundation.org> * fix case where sub-type of QoS is used Signed-off-by: William Woodall <william@osrfoundation.org> * fixup get_node_topics_interface.hpp according to reviews and tests Signed-off-by: William Woodall <william@osrfoundation.org> * additional fixes based on local testing and CI Signed-off-by: William Woodall <william@osrfoundation.org> * another trick to avoid 'no appropriate default constructor available' Signed-off-by: William Woodall <william@osrfoundation.org> * fix compiler error with clang on macOS Signed-off-by: William Woodall <william@osrfoundation.org> * disable build failure tests until we can get Jenkins to ignore their output Signed-off-by: William Woodall <william@osrfoundation.org> * suppress more cppcheck false positives Signed-off-by: William Woodall <william@osrfoundation.org> * add missing visibility macros to default QoS profile classes Signed-off-by: William Woodall <william@osrfoundation.org> * fix another case of 'no appropriate default constructor available' Signed-off-by: William Woodall <william@osrfoundation.org> * unfortunately this actaully fixes a build error on Windows... Signed-off-by: William Woodall <william@osrfoundation.org> * fix typos Signed-off-by: William Woodall <william@osrfoundation.org>
This commit is contained in:
parent
385cccc2cc
commit
c769b1b030
53 changed files with 1908 additions and 454 deletions
|
@ -65,6 +65,7 @@ set(${PROJECT_NAME}_SRCS
|
|||
src/rclcpp/parameter_map.cpp
|
||||
src/rclcpp/parameter_service.cpp
|
||||
src/rclcpp/publisher_base.cpp
|
||||
src/rclcpp/qos.cpp
|
||||
src/rclcpp/qos_event.cpp
|
||||
src/rclcpp/service.cpp
|
||||
src/rclcpp/signal_handler.cpp
|
||||
|
@ -142,6 +143,8 @@ if(BUILD_TESTING)
|
|||
|
||||
find_package(rmw_implementation_cmake REQUIRED)
|
||||
|
||||
include(cmake/rclcpp_add_build_failure_test.cmake)
|
||||
|
||||
ament_add_gtest(test_client test/test_client.cpp)
|
||||
if(TARGET test_client)
|
||||
ament_target_dependencies(test_client
|
||||
|
@ -201,6 +204,34 @@ if(BUILD_TESTING)
|
|||
)
|
||||
target_link_libraries(test_node ${PROJECT_NAME})
|
||||
endif()
|
||||
|
||||
ament_add_gtest(test_node_interfaces__get_node_interfaces
|
||||
test/node_interfaces/test_get_node_interfaces.cpp)
|
||||
if(TARGET test_node_interfaces__get_node_interfaces)
|
||||
target_link_libraries(test_node_interfaces__get_node_interfaces ${PROJECT_NAME})
|
||||
endif()
|
||||
|
||||
# TODO(wjwwood): reenable these build failure tests when I can get Jenkins to ignore their output
|
||||
# rclcpp_add_build_failure_test(build_failure__get_node_topics_interface_const_ref_rclcpp_node
|
||||
# test/node_interfaces/test_does_not_compile/get_node_topics_interface_const_ref_rclcpp_node.cpp)
|
||||
# target_link_libraries(build_failure__get_node_topics_interface_const_ref_rclcpp_node
|
||||
# ${PROJECT_NAME})
|
||||
|
||||
# rclcpp_add_build_failure_test(build_failure__get_node_topics_interface_const_ptr_rclcpp_node
|
||||
# test/node_interfaces/test_does_not_compile/get_node_topics_interface_const_ptr_rclcpp_node.cpp)
|
||||
# target_link_libraries(build_failure__get_node_topics_interface_const_ptr_rclcpp_node
|
||||
# ${PROJECT_NAME})
|
||||
|
||||
# rclcpp_add_build_failure_test(build_failure__get_node_topics_interface_const_ref_wrapped_node
|
||||
# test/node_interfaces/test_does_not_compile/get_node_topics_interface_const_ref_wrapped_node.cpp)
|
||||
# target_link_libraries(build_failure__get_node_topics_interface_const_ref_rclcpp_node
|
||||
# ${PROJECT_NAME})
|
||||
|
||||
# rclcpp_add_build_failure_test(build_failure__get_node_topics_interface_const_ptr_wrapped_node
|
||||
# test/node_interfaces/test_does_not_compile/get_node_topics_interface_const_ptr_wrapped_node.cpp)
|
||||
# target_link_libraries(build_failure__get_node_topics_interface_const_ptr_rclcpp_node
|
||||
# ${PROJECT_NAME})
|
||||
|
||||
ament_add_gtest(test_node_global_args test/test_node_global_args.cpp)
|
||||
if(TARGET test_node_global_args)
|
||||
ament_target_dependencies(test_node_global_args
|
||||
|
@ -245,15 +276,6 @@ if(BUILD_TESTING)
|
|||
)
|
||||
target_link_libraries(test_publisher ${PROJECT_NAME})
|
||||
endif()
|
||||
ament_add_gtest(test_pub_sub_option_interface test/test_pub_sub_option_interface.cpp)
|
||||
if(TARGET test_pub_sub_option_interface)
|
||||
ament_target_dependencies(test_pub_sub_option_interface
|
||||
test_msgs
|
||||
)
|
||||
target_link_libraries(test_pub_sub_option_interface
|
||||
${PROJECT_NAME}
|
||||
)
|
||||
endif()
|
||||
ament_add_gtest(test_publisher_subscription_count_api test/test_publisher_subscription_count_api.cpp)
|
||||
if(TARGET test_publisher_subscription_count_api)
|
||||
ament_target_dependencies(test_publisher_subscription_count_api
|
||||
|
|
56
rclcpp/cmake/rclcpp_add_build_failure_test.cmake
Normal file
56
rclcpp/cmake/rclcpp_add_build_failure_test.cmake
Normal file
|
@ -0,0 +1,56 @@
|
|||
# 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.
|
||||
|
||||
#
|
||||
# Register a test which tries to compile a file and expects it to fail to build.
|
||||
#
|
||||
# This will create two targets, one by the given target name and a test target
|
||||
# which has the same name prefixed with `test_`.
|
||||
# For example, if target is `should_not_compile__use_const_argument` then there
|
||||
# will be an executable target called `should_not_compile__use_const_argument`
|
||||
# and a test target called `test_should_not_compile__use_const_argument`.
|
||||
#
|
||||
# :param target: the name of the target to be created
|
||||
# :type target: string
|
||||
# :param ARGN: the list of source files to be used to create the test executable
|
||||
# :type ARGN: list of strings
|
||||
#
|
||||
macro(rclcpp_add_build_failure_test target)
|
||||
if(${ARGC} EQUAL 0)
|
||||
message(
|
||||
FATAL_ERROR
|
||||
"rclcpp_add_build_failure_test() requires a target name and "
|
||||
"at least one source file")
|
||||
endif()
|
||||
|
||||
add_executable(${target} ${ARGN})
|
||||
set_target_properties(${target}
|
||||
PROPERTIES
|
||||
EXCLUDE_FROM_ALL TRUE
|
||||
EXCLUDE_FROM_DEFAULT_BUILD TRUE)
|
||||
|
||||
add_test(
|
||||
NAME test_${target}
|
||||
COMMAND
|
||||
${CMAKE_COMMAND}
|
||||
--build .
|
||||
--target ${target}
|
||||
--config $<CONFIGURATION>
|
||||
WORKING_DIRECTORY ${CMAKE_BINARY_DIR})
|
||||
set_tests_properties(test_${target}
|
||||
PROPERTIES
|
||||
WILL_FAIL TRUE
|
||||
LABELS "build_failure"
|
||||
)
|
||||
endmacro()
|
|
@ -65,7 +65,8 @@ void * retyped_reallocate(void * untyped_pointer, size_t size, void * untyped_al
|
|||
|
||||
// Convert a std::allocator_traits-formatted Allocator into an rcl allocator
|
||||
template<
|
||||
typename T, typename Alloc,
|
||||
typename T,
|
||||
typename Alloc,
|
||||
typename std::enable_if<!std::is_same<Alloc, std::allocator<void>>::value>::type * = nullptr>
|
||||
rcl_allocator_t get_rcl_allocator(Alloc & allocator)
|
||||
{
|
||||
|
@ -83,7 +84,8 @@ rcl_allocator_t get_rcl_allocator(Alloc & allocator)
|
|||
|
||||
// TODO(jacquelinekay) Workaround for an incomplete implementation of std::allocator<void>
|
||||
template<
|
||||
typename T, typename Alloc,
|
||||
typename T,
|
||||
typename Alloc,
|
||||
typename std::enable_if<std::is_same<Alloc, std::allocator<void>>::value>::type * = nullptr>
|
||||
rcl_allocator_t get_rcl_allocator(Alloc & allocator)
|
||||
{
|
||||
|
|
|
@ -18,14 +18,23 @@
|
|||
#include <memory>
|
||||
#include <string>
|
||||
|
||||
#include "rclcpp/node_interfaces/get_node_topics_interface.hpp"
|
||||
#include "rclcpp/node_interfaces/node_topics_interface.hpp"
|
||||
#include "rclcpp/node_options.hpp"
|
||||
#include "rclcpp/publisher_factory.hpp"
|
||||
#include "rclcpp/publisher_options.hpp"
|
||||
#include "rclcpp/qos.hpp"
|
||||
#include "rmw/qos_profiles.h"
|
||||
|
||||
namespace rclcpp
|
||||
{
|
||||
|
||||
template<typename MessageT, typename AllocatorT, typename PublisherT>
|
||||
template<
|
||||
typename MessageT,
|
||||
typename AllocatorT = std::allocator<void>,
|
||||
typename PublisherT = ::rclcpp::Publisher<MessageT, AllocatorT>>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated("use alternative rclcpp::create_publisher() signatures")]]
|
||||
std::shared_ptr<PublisherT>
|
||||
create_publisher(
|
||||
rclcpp::node_interfaces::NodeTopicsInterface * node_topics,
|
||||
|
@ -50,6 +59,63 @@ create_publisher(
|
|||
return std::dynamic_pointer_cast<PublisherT>(pub);
|
||||
}
|
||||
|
||||
/// Create and return a publisher of the given MessageT type.
|
||||
/**
|
||||
* The NodeT type only needs to have a method called get_node_topics_interface()
|
||||
* which returns a shared_ptr to a NodeTopicsInterface.
|
||||
*/
|
||||
template<
|
||||
typename MessageT,
|
||||
typename AllocatorT = std::allocator<void>,
|
||||
typename PublisherT = ::rclcpp::Publisher<MessageT, AllocatorT>,
|
||||
typename NodeT>
|
||||
std::shared_ptr<PublisherT>
|
||||
create_publisher(
|
||||
NodeT & node,
|
||||
const std::string & topic_name,
|
||||
const rclcpp::QoS & qos,
|
||||
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = (
|
||||
rclcpp::PublisherOptionsWithAllocator<AllocatorT>()
|
||||
))
|
||||
{
|
||||
using rclcpp::node_interfaces::get_node_topics_interface;
|
||||
auto node_topics = get_node_topics_interface(node);
|
||||
|
||||
std::shared_ptr<AllocatorT> allocator = options.allocator;
|
||||
if (!allocator) {
|
||||
allocator = std::make_shared<AllocatorT>();
|
||||
}
|
||||
|
||||
bool use_intra_process;
|
||||
switch (options.use_intra_process_comm) {
|
||||
case IntraProcessSetting::Enable:
|
||||
use_intra_process = true;
|
||||
break;
|
||||
case IntraProcessSetting::Disable:
|
||||
use_intra_process = false;
|
||||
break;
|
||||
case IntraProcessSetting::NodeDefault:
|
||||
use_intra_process = node_topics->get_node_base_interface()->get_use_intra_process_default();
|
||||
break;
|
||||
default:
|
||||
throw std::runtime_error("Unrecognized IntraProcessSetting value");
|
||||
break;
|
||||
}
|
||||
|
||||
// TODO(wjwwood): convert all of the interfaces to use QoS and PublisherOptionsBase
|
||||
auto pub = node_topics->create_publisher(
|
||||
topic_name,
|
||||
rclcpp::create_publisher_factory<MessageT, AllocatorT, PublisherT>(
|
||||
options.event_callbacks,
|
||||
allocator
|
||||
),
|
||||
options.template to_rcl_publisher_options<MessageT>(qos),
|
||||
use_intra_process
|
||||
);
|
||||
node_topics->add_publisher(pub, options.callback_group);
|
||||
return std::dynamic_pointer_cast<PublisherT>(pub);
|
||||
}
|
||||
|
||||
} // namespace rclcpp
|
||||
|
||||
#endif // RCLCPP__CREATE_PUBLISHER_HPP_
|
||||
|
|
|
@ -19,8 +19,11 @@
|
|||
#include <string>
|
||||
#include <utility>
|
||||
|
||||
#include "rclcpp/node_interfaces/get_node_topics_interface.hpp"
|
||||
#include "rclcpp/node_interfaces/node_topics_interface.hpp"
|
||||
#include "rclcpp/subscription_factory.hpp"
|
||||
#include "rclcpp/subscription_options.hpp"
|
||||
#include "rclcpp/qos.hpp"
|
||||
#include "rmw/qos_profiles.h"
|
||||
|
||||
namespace rclcpp
|
||||
|
@ -32,6 +35,8 @@ template<
|
|||
typename AllocatorT,
|
||||
typename CallbackMessageT,
|
||||
typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated("use alternative rclcpp::create_subscription() signatures")]]
|
||||
typename std::shared_ptr<SubscriptionT>
|
||||
create_subscription(
|
||||
rclcpp::node_interfaces::NodeTopicsInterface * node_topics,
|
||||
|
@ -67,6 +72,75 @@ create_subscription(
|
|||
return std::dynamic_pointer_cast<SubscriptionT>(sub);
|
||||
}
|
||||
|
||||
/// Create and return a subscription of the given MessageT type.
|
||||
/**
|
||||
* 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 MessageT,
|
||||
typename CallbackT,
|
||||
typename AllocatorT = std::allocator<void>,
|
||||
typename CallbackMessageT =
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type,
|
||||
typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>,
|
||||
typename NodeT>
|
||||
typename std::shared_ptr<SubscriptionT>
|
||||
create_subscription(
|
||||
NodeT && node,
|
||||
const std::string & topic_name,
|
||||
const rclcpp::QoS & qos,
|
||||
CallbackT && callback,
|
||||
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
|
||||
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
|
||||
),
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
|
||||
CallbackMessageT, AllocatorT>::SharedPtr
|
||||
msg_mem_strat = nullptr)
|
||||
{
|
||||
using rclcpp::node_interfaces::get_node_topics_interface;
|
||||
auto node_topics = get_node_topics_interface(std::forward<NodeT>(node));
|
||||
|
||||
if (!msg_mem_strat) {
|
||||
using rclcpp::message_memory_strategy::MessageMemoryStrategy;
|
||||
msg_mem_strat = MessageMemoryStrategy<CallbackMessageT, AllocatorT>::create_default();
|
||||
}
|
||||
|
||||
std::shared_ptr<AllocatorT> allocator = options.allocator;
|
||||
if (!allocator) {
|
||||
allocator = std::make_shared<AllocatorT>();
|
||||
}
|
||||
auto factory = rclcpp::create_subscription_factory
|
||||
<MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT>(
|
||||
std::forward<CallbackT>(callback), options.event_callbacks, msg_mem_strat, allocator);
|
||||
|
||||
bool use_intra_process;
|
||||
switch (options.use_intra_process_comm) {
|
||||
case IntraProcessSetting::Enable:
|
||||
use_intra_process = true;
|
||||
break;
|
||||
case IntraProcessSetting::Disable:
|
||||
use_intra_process = false;
|
||||
break;
|
||||
case IntraProcessSetting::NodeDefault:
|
||||
use_intra_process = node_topics->get_node_base_interface()->get_use_intra_process_default();
|
||||
break;
|
||||
default:
|
||||
throw std::runtime_error("Unrecognized IntraProcessSetting value");
|
||||
break;
|
||||
}
|
||||
|
||||
// TODO(wjwwood): convert all of the interfaces to use QoS and SubscriptionOptionsBase
|
||||
auto sub = node_topics->create_subscription(
|
||||
topic_name,
|
||||
factory,
|
||||
options.template to_rcl_subscription_options<MessageT>(qos),
|
||||
use_intra_process);
|
||||
node_topics->add_subscription(sub, options.callback_group);
|
||||
return std::dynamic_pointer_cast<SubscriptionT>(sub);
|
||||
}
|
||||
|
||||
} // namespace rclcpp
|
||||
|
||||
#endif // RCLCPP__CREATE_SUBSCRIPTION_HPP_
|
||||
|
|
|
@ -23,91 +23,87 @@
|
|||
|
||||
namespace rclcpp
|
||||
{
|
||||
class Duration
|
||||
class RCLCPP_PUBLIC Duration
|
||||
{
|
||||
public:
|
||||
RCLCPP_PUBLIC
|
||||
Duration(int32_t seconds, uint32_t nanoseconds);
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
explicit Duration(
|
||||
rcl_duration_value_t nanoseconds);
|
||||
explicit Duration(rcl_duration_value_t nanoseconds);
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
explicit Duration(
|
||||
std::chrono::nanoseconds nanoseconds);
|
||||
explicit Duration(std::chrono::nanoseconds nanoseconds);
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
Duration(
|
||||
const builtin_interfaces::msg::Duration & duration_msg);
|
||||
// intentionally not using explicit to create a conversion constructor
|
||||
template<class Rep, class Period>
|
||||
// cppcheck-suppress noExplicitConstructor
|
||||
Duration(const std::chrono::duration<Rep, Period> & duration) // NOLINT(runtime/explicit)
|
||||
: Duration(std::chrono::duration_cast<std::chrono::nanoseconds>(duration))
|
||||
{}
|
||||
|
||||
// cppcheck-suppress noExplicitConstructor
|
||||
Duration(const builtin_interfaces::msg::Duration & duration_msg); // NOLINT(runtime/explicit)
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
explicit Duration(const rcl_duration_t & duration);
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
Duration(const Duration & rhs);
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
virtual ~Duration();
|
||||
virtual ~Duration() = default;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
operator builtin_interfaces::msg::Duration() const;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
// cppcheck-suppress operatorEq // this is a false positive from cppcheck
|
||||
Duration &
|
||||
operator=(const Duration & rhs);
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
Duration &
|
||||
operator=(const builtin_interfaces::msg::Duration & Duration_msg);
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
bool
|
||||
operator==(const rclcpp::Duration & rhs) const;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
bool
|
||||
operator<(const rclcpp::Duration & rhs) const;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
bool
|
||||
operator<=(const rclcpp::Duration & rhs) const;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
bool
|
||||
operator>=(const rclcpp::Duration & rhs) const;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
bool
|
||||
operator>(const rclcpp::Duration & rhs) const;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
Duration
|
||||
operator+(const rclcpp::Duration & rhs) const;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
Duration
|
||||
operator-(const rclcpp::Duration & rhs) const;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
static Duration
|
||||
static
|
||||
Duration
|
||||
max();
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
Duration
|
||||
operator*(double scale) const;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
rcl_duration_value_t
|
||||
nanoseconds() const;
|
||||
|
||||
/// \return the duration in seconds as a floating point number.
|
||||
/// \warning Depending on sizeof(double) there could be significant precision loss.
|
||||
/// When an exact time is required use nanoseconds() instead.
|
||||
RCLCPP_PUBLIC
|
||||
double
|
||||
seconds() const;
|
||||
|
||||
template<class DurationT>
|
||||
DurationT
|
||||
to_chrono() const
|
||||
{
|
||||
return std::chrono::duration_cast<DurationT>(std::chrono::nanoseconds(this->nanoseconds()));
|
||||
}
|
||||
|
||||
rmw_time_t
|
||||
to_rmw_time() const;
|
||||
|
||||
private:
|
||||
rcl_duration_t rcl_duration_;
|
||||
};
|
||||
|
|
|
@ -42,7 +42,6 @@
|
|||
#include "rclcpp/logger.hpp"
|
||||
#include "rclcpp/macros.hpp"
|
||||
#include "rclcpp/message_memory_strategy.hpp"
|
||||
#include "rclcpp/node_options.hpp"
|
||||
#include "rclcpp/node_interfaces/node_base_interface.hpp"
|
||||
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
|
||||
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
|
||||
|
@ -53,9 +52,11 @@
|
|||
#include "rclcpp/node_interfaces/node_timers_interface.hpp"
|
||||
#include "rclcpp/node_interfaces/node_topics_interface.hpp"
|
||||
#include "rclcpp/node_interfaces/node_waitables_interface.hpp"
|
||||
#include "rclcpp/node_options.hpp"
|
||||
#include "rclcpp/parameter.hpp"
|
||||
#include "rclcpp/publisher.hpp"
|
||||
#include "rclcpp/publisher_options.hpp"
|
||||
#include "rclcpp/qos.hpp"
|
||||
#include "rclcpp/service.hpp"
|
||||
#include "rclcpp/subscription.hpp"
|
||||
#include "rclcpp/subscription_options.hpp"
|
||||
|
@ -144,8 +145,27 @@ public:
|
|||
|
||||
/// Create and return a Publisher.
|
||||
/**
|
||||
* The rclcpp::QoS has several convenient constructors, including a
|
||||
* conversion constructor for size_t, which mimics older API's that
|
||||
* allows just a string and size_t to create a publisher.
|
||||
*
|
||||
* For example, all of these cases will work:
|
||||
*
|
||||
* pub = node->create_publisher<MsgT>("chatter", 10); // implicitly KeepLast
|
||||
* pub = node->create_publisher<MsgT>("chatter", QoS(10)); // implicitly KeepLast
|
||||
* pub = node->create_publisher<MsgT>("chatter", QoS(KeepLast(10)));
|
||||
* pub = node->create_publisher<MsgT>("chatter", QoS(KeepAll()));
|
||||
* pub = node->create_publisher<MsgT>("chatter", QoS(1).best_effort().volatile());
|
||||
* {
|
||||
* rclcpp::QoS custom_qos(KeepLast(10), rmw_qos_profile_sensor_data);
|
||||
* pub = node->create_publisher<MsgT>("chatter", custom_qos);
|
||||
* }
|
||||
*
|
||||
* The publisher options may optionally be passed as the third argument for
|
||||
* any of the above cases.
|
||||
*
|
||||
* \param[in] topic_name The topic for this publisher to publish on.
|
||||
* \param[in] qos_history_depth The depth of the publisher message queue.
|
||||
* \param[in] qos The Quality of Service settings for the publisher.
|
||||
* \param[in] options Additional options for the created Publisher.
|
||||
* \return Shared pointer to the created publisher.
|
||||
*/
|
||||
|
@ -156,30 +176,29 @@ public:
|
|||
std::shared_ptr<PublisherT>
|
||||
create_publisher(
|
||||
const std::string & topic_name,
|
||||
size_t qos_history_depth,
|
||||
const PublisherOptionsWithAllocator<AllocatorT> &
|
||||
options = PublisherOptionsWithAllocator<AllocatorT>());
|
||||
const rclcpp::QoS & qos,
|
||||
const PublisherOptionsWithAllocator<AllocatorT> & options =
|
||||
PublisherOptionsWithAllocator<AllocatorT>()
|
||||
);
|
||||
|
||||
/// Create and return a Publisher.
|
||||
/**
|
||||
* \param[in] topic_name The topic for this publisher to publish on.
|
||||
* \param[in] qos_history_depth The depth of the publisher message queue.
|
||||
* \param[in] allocator Optional custom allocator.
|
||||
* \param[in] allocator Custom allocator.
|
||||
* \return Shared pointer to the created publisher.
|
||||
*/
|
||||
template<
|
||||
typename MessageT, typename Alloc = std::allocator<void>,
|
||||
typename PublisherT = ::rclcpp::Publisher<MessageT, Alloc>>
|
||||
typename MessageT,
|
||||
typename AllocatorT = std::allocator<void>,
|
||||
typename PublisherT = ::rclcpp::Publisher<MessageT, AllocatorT>>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated(
|
||||
"use the create_publisher(const std::string &, size_t, const PublisherOptions<Alloc> & = "
|
||||
"PublisherOptions<Alloc>()) signature instead")]]
|
||||
[[deprecated("use create_publisher(const std::string &, const rclcpp::QoS &, ...) instead")]]
|
||||
std::shared_ptr<PublisherT>
|
||||
create_publisher(
|
||||
const std::string & topic_name,
|
||||
size_t qos_history_depth,
|
||||
std::shared_ptr<Alloc> allocator,
|
||||
IntraProcessSetting use_intra_process_comm = IntraProcessSetting::NodeDefault);
|
||||
std::shared_ptr<AllocatorT> allocator);
|
||||
|
||||
/// Create and return a Publisher.
|
||||
/**
|
||||
|
@ -189,14 +208,16 @@ public:
|
|||
* \return Shared pointer to the created publisher.
|
||||
*/
|
||||
template<
|
||||
typename MessageT, typename Alloc = std::allocator<void>,
|
||||
typename PublisherT = ::rclcpp::Publisher<MessageT, Alloc>>
|
||||
typename MessageT,
|
||||
typename AllocatorT = std::allocator<void>,
|
||||
typename PublisherT = ::rclcpp::Publisher<MessageT, AllocatorT>>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated("use create_publisher(const std::string &, const rclcpp::QoS &, ...) instead")]]
|
||||
std::shared_ptr<PublisherT>
|
||||
create_publisher(
|
||||
const std::string & topic_name,
|
||||
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
|
||||
std::shared_ptr<Alloc> allocator = nullptr,
|
||||
IntraProcessSetting use_intra_process_comm = IntraProcessSetting::NodeDefault);
|
||||
std::shared_ptr<AllocatorT> allocator = nullptr);
|
||||
|
||||
/// Create and return a Subscription.
|
||||
/**
|
||||
|
@ -220,10 +241,10 @@ public:
|
|||
std::shared_ptr<SubscriptionT>
|
||||
create_subscription(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::QoS & qos,
|
||||
CallbackT && callback,
|
||||
size_t qos_history_depth,
|
||||
const SubscriptionOptionsWithAllocator<AllocatorT> &
|
||||
options = SubscriptionOptionsWithAllocator<AllocatorT>(),
|
||||
const SubscriptionOptionsWithAllocator<AllocatorT> & options =
|
||||
SubscriptionOptionsWithAllocator<AllocatorT>(),
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, AllocatorT
|
||||
>::SharedPtr
|
||||
|
@ -250,6 +271,10 @@ public:
|
|||
typename Alloc = std::allocator<void>,
|
||||
typename SubscriptionT = rclcpp::Subscription<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated(
|
||||
"use create_subscription(const std::string &, const rclcpp::QoS &, CallbackT, ...) instead"
|
||||
)]]
|
||||
std::shared_ptr<SubscriptionT>
|
||||
create_subscription(
|
||||
const std::string & topic_name,
|
||||
|
@ -260,8 +285,7 @@ public:
|
|||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>::SharedPtr
|
||||
msg_mem_strat = nullptr,
|
||||
std::shared_ptr<Alloc> allocator = nullptr,
|
||||
IntraProcessSetting use_intra_process_comm = IntraProcessSetting::NodeDefault);
|
||||
std::shared_ptr<Alloc> allocator = nullptr);
|
||||
|
||||
/// Create and return a Subscription.
|
||||
/**
|
||||
|
@ -284,21 +308,21 @@ public:
|
|||
typename Alloc = std::allocator<void>,
|
||||
typename SubscriptionT = rclcpp::Subscription<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated(
|
||||
"use the create_subscription(const std::string &, CallbackT &&, size_t, "
|
||||
"const SubscriptionOptions<Alloc> & = SubscriptionOptions<Alloc>(), ...) signature instead")]]
|
||||
"use create_subscription(const std::string &, const rclcpp::QoS &, CallbackT, ...) instead"
|
||||
)]]
|
||||
std::shared_ptr<SubscriptionT>
|
||||
create_subscription(
|
||||
const std::string & topic_name,
|
||||
CallbackT && callback,
|
||||
size_t qos_history_depth,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
|
||||
bool ignore_local_publications = false,
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>::SharedPtr
|
||||
msg_mem_strat = nullptr,
|
||||
std::shared_ptr<Alloc> allocator = nullptr,
|
||||
IntraProcessSetting use_intra_process_comm = IntraProcessSetting::NodeDefault);
|
||||
std::shared_ptr<Alloc> allocator = nullptr);
|
||||
|
||||
/// Create a timer.
|
||||
/**
|
||||
|
@ -1118,12 +1142,12 @@ public:
|
|||
* with a leading '/'.
|
||||
*/
|
||||
RCLCPP_PUBLIC
|
||||
Node::SharedPtr
|
||||
rclcpp::Node::SharedPtr
|
||||
create_sub_node(const std::string & sub_namespace);
|
||||
|
||||
/// Return the NodeOptions used when creating this node.
|
||||
RCLCPP_PUBLIC
|
||||
const NodeOptions &
|
||||
const rclcpp::NodeOptions &
|
||||
get_node_options() const;
|
||||
|
||||
/// Manually assert that this Node is alive (for RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_NODE).
|
||||
|
@ -1170,7 +1194,7 @@ private:
|
|||
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
|
||||
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
|
||||
|
||||
const NodeOptions node_options_;
|
||||
const rclcpp::NodeOptions node_options_;
|
||||
const std::string sub_namespace_;
|
||||
const std::string effective_namespace_;
|
||||
};
|
||||
|
|
|
@ -36,11 +36,12 @@
|
|||
#include "rcl_interfaces/msg/intra_process_message.hpp"
|
||||
|
||||
#include "rclcpp/contexts/default_context.hpp"
|
||||
#include "rclcpp/intra_process_manager.hpp"
|
||||
#include "rclcpp/parameter.hpp"
|
||||
#include "rclcpp/create_publisher.hpp"
|
||||
#include "rclcpp/create_service.hpp"
|
||||
#include "rclcpp/create_subscription.hpp"
|
||||
#include "rclcpp/intra_process_manager.hpp"
|
||||
#include "rclcpp/parameter.hpp"
|
||||
#include "rclcpp/qos.hpp"
|
||||
#include "rclcpp/type_support_decl.hpp"
|
||||
#include "rclcpp/visibility_control.hpp"
|
||||
|
||||
|
@ -67,68 +68,42 @@ template<typename MessageT, typename AllocatorT, typename PublisherT>
|
|||
std::shared_ptr<PublisherT>
|
||||
Node::create_publisher(
|
||||
const std::string & topic_name,
|
||||
size_t qos_history_depth,
|
||||
const rclcpp::QoS & qos,
|
||||
const PublisherOptionsWithAllocator<AllocatorT> & options)
|
||||
{
|
||||
std::shared_ptr<AllocatorT> allocator = options.allocator;
|
||||
if (!allocator) {
|
||||
allocator = std::make_shared<AllocatorT>();
|
||||
}
|
||||
rmw_qos_profile_t qos_profile = options.qos_profile;
|
||||
qos_profile.depth = qos_history_depth;
|
||||
|
||||
bool use_intra_process;
|
||||
switch (options.use_intra_process_comm) {
|
||||
case IntraProcessSetting::Enable:
|
||||
use_intra_process = true;
|
||||
break;
|
||||
case IntraProcessSetting::Disable:
|
||||
use_intra_process = false;
|
||||
break;
|
||||
case IntraProcessSetting::NodeDefault:
|
||||
use_intra_process = this->get_node_options().use_intra_process_comms();
|
||||
break;
|
||||
default:
|
||||
throw std::runtime_error("Unrecognized IntraProcessSetting value");
|
||||
break;
|
||||
}
|
||||
|
||||
return rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
|
||||
this->node_topics_.get(),
|
||||
*this,
|
||||
extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
|
||||
qos_profile,
|
||||
options.event_callbacks,
|
||||
options.callback_group,
|
||||
use_intra_process,
|
||||
allocator);
|
||||
qos,
|
||||
options);
|
||||
}
|
||||
|
||||
template<typename MessageT, typename Alloc, typename PublisherT>
|
||||
template<typename MessageT, typename AllocatorT, typename PublisherT>
|
||||
std::shared_ptr<PublisherT>
|
||||
Node::create_publisher(
|
||||
const std::string & topic_name, size_t qos_history_depth,
|
||||
std::shared_ptr<Alloc> allocator,
|
||||
IntraProcessSetting use_intra_process_comm)
|
||||
const std::string & topic_name,
|
||||
size_t qos_history_depth,
|
||||
std::shared_ptr<AllocatorT> allocator)
|
||||
{
|
||||
PublisherOptionsWithAllocator<Alloc> pub_options;
|
||||
PublisherOptionsWithAllocator<AllocatorT> pub_options;
|
||||
pub_options.allocator = allocator;
|
||||
pub_options.use_intra_process_comm = use_intra_process_comm;
|
||||
return this->create_publisher<MessageT, Alloc, PublisherT>(
|
||||
topic_name, qos_history_depth, pub_options);
|
||||
return this->create_publisher<MessageT, AllocatorT, PublisherT>(
|
||||
topic_name, rclcpp::QoS(rclcpp::KeepLast(qos_history_depth)), pub_options);
|
||||
}
|
||||
|
||||
template<typename MessageT, typename Alloc, typename PublisherT>
|
||||
template<typename MessageT, typename AllocatorT, typename PublisherT>
|
||||
std::shared_ptr<PublisherT>
|
||||
Node::create_publisher(
|
||||
const std::string & topic_name, const rmw_qos_profile_t & qos_profile,
|
||||
std::shared_ptr<Alloc> allocator, IntraProcessSetting use_intra_process_comm)
|
||||
const std::string & topic_name,
|
||||
const rmw_qos_profile_t & qos_profile,
|
||||
std::shared_ptr<AllocatorT> allocator)
|
||||
{
|
||||
PublisherOptionsWithAllocator<Alloc> pub_options;
|
||||
pub_options.qos_profile = qos_profile;
|
||||
rclcpp::QoS qos(rclcpp::QoSInitialization::from_rmw(qos_profile));
|
||||
qos.get_rmw_qos_profile() = qos_profile;
|
||||
|
||||
PublisherOptionsWithAllocator<AllocatorT> pub_options;
|
||||
pub_options.allocator = allocator;
|
||||
pub_options.use_intra_process_comm = use_intra_process_comm;
|
||||
return this->create_publisher<MessageT, Alloc, PublisherT>(
|
||||
topic_name, qos_profile.depth, pub_options);
|
||||
return this->create_publisher<MessageT, AllocatorT, PublisherT>(topic_name, qos, pub_options);
|
||||
}
|
||||
|
||||
template<
|
||||
|
@ -139,56 +114,20 @@ template<
|
|||
std::shared_ptr<SubscriptionT>
|
||||
Node::create_subscription(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::QoS & qos,
|
||||
CallbackT && callback,
|
||||
size_t qos_history_depth,
|
||||
const SubscriptionOptionsWithAllocator<AllocatorT> & options,
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, AllocatorT>::SharedPtr
|
||||
msg_mem_strat)
|
||||
{
|
||||
using CallbackMessageT = typename rclcpp::subscription_traits::has_message_type<CallbackT>::type;
|
||||
|
||||
std::shared_ptr<AllocatorT> allocator = options.allocator;
|
||||
if (!allocator) {
|
||||
allocator = std::make_shared<AllocatorT>();
|
||||
}
|
||||
|
||||
rmw_qos_profile_t qos_profile = options.qos_profile;
|
||||
qos_profile.depth = qos_history_depth;
|
||||
|
||||
if (!msg_mem_strat) {
|
||||
using rclcpp::message_memory_strategy::MessageMemoryStrategy;
|
||||
msg_mem_strat = MessageMemoryStrategy<CallbackMessageT, AllocatorT>::create_default();
|
||||
}
|
||||
|
||||
bool use_intra_process;
|
||||
switch (options.use_intra_process_comm) {
|
||||
case IntraProcessSetting::Enable:
|
||||
use_intra_process = true;
|
||||
break;
|
||||
case IntraProcessSetting::Disable:
|
||||
use_intra_process = false;
|
||||
break;
|
||||
case IntraProcessSetting::NodeDefault:
|
||||
use_intra_process = this->get_node_options().use_intra_process_comms();
|
||||
break;
|
||||
default:
|
||||
throw std::runtime_error("Unrecognized IntraProcessSetting value");
|
||||
break;
|
||||
}
|
||||
|
||||
return rclcpp::create_subscription<
|
||||
MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT>(
|
||||
this->node_topics_.get(),
|
||||
return rclcpp::create_subscription<MessageT>(
|
||||
*this,
|
||||
extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
|
||||
qos,
|
||||
std::forward<CallbackT>(callback),
|
||||
qos_profile,
|
||||
options.event_callbacks,
|
||||
options.callback_group,
|
||||
options.ignore_local_publications,
|
||||
use_intra_process,
|
||||
msg_mem_strat,
|
||||
allocator);
|
||||
options,
|
||||
msg_mem_strat);
|
||||
}
|
||||
|
||||
template<
|
||||
|
@ -206,18 +145,18 @@ Node::create_subscription(
|
|||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>::SharedPtr
|
||||
msg_mem_strat,
|
||||
std::shared_ptr<Alloc> allocator,
|
||||
IntraProcessSetting use_intra_process_comm)
|
||||
std::shared_ptr<Alloc> allocator)
|
||||
{
|
||||
rclcpp::QoS qos(rclcpp::QoSInitialization::from_rmw(qos_profile));
|
||||
qos.get_rmw_qos_profile() = qos_profile;
|
||||
|
||||
SubscriptionOptionsWithAllocator<Alloc> sub_options;
|
||||
sub_options.qos_profile = qos_profile;
|
||||
sub_options.callback_group = group;
|
||||
sub_options.ignore_local_publications = ignore_local_publications;
|
||||
sub_options.allocator = allocator;
|
||||
sub_options.use_intra_process_comm = use_intra_process_comm;
|
||||
|
||||
return this->create_subscription<MessageT, CallbackT, Alloc, SubscriptionT>(
|
||||
topic_name, std::forward<CallbackT>(callback), qos_profile.depth, sub_options, msg_mem_strat);
|
||||
topic_name, qos, std::forward<CallbackT>(callback), sub_options, msg_mem_strat);
|
||||
}
|
||||
|
||||
template<
|
||||
|
@ -235,17 +174,19 @@ Node::create_subscription(
|
|||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>::SharedPtr
|
||||
msg_mem_strat,
|
||||
std::shared_ptr<Alloc> allocator,
|
||||
IntraProcessSetting use_intra_process_comm)
|
||||
std::shared_ptr<Alloc> allocator)
|
||||
{
|
||||
SubscriptionOptionsWithAllocator<Alloc> sub_options;
|
||||
sub_options.callback_group = group;
|
||||
sub_options.ignore_local_publications = ignore_local_publications;
|
||||
sub_options.allocator = allocator;
|
||||
sub_options.use_intra_process_comm = use_intra_process_comm;
|
||||
|
||||
return this->create_subscription<MessageT, CallbackT, Alloc, SubscriptionT>(
|
||||
topic_name, std::forward<CallbackT>(callback), qos_history_depth, sub_options, msg_mem_strat);
|
||||
topic_name,
|
||||
rclcpp::QoS(rclcpp::KeepLast(qos_history_depth)),
|
||||
std::forward<CallbackT>(callback),
|
||||
sub_options,
|
||||
msg_mem_strat);
|
||||
}
|
||||
|
||||
template<typename DurationRepT, typename DurationT, typename CallbackT>
|
||||
|
|
|
@ -0,0 +1,147 @@
|
|||
// 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.
|
||||
|
||||
#ifndef RCLCPP__NODE_INTERFACES__GET_NODE_TOPICS_INTERFACE_HPP_
|
||||
#define RCLCPP__NODE_INTERFACES__GET_NODE_TOPICS_INTERFACE_HPP_
|
||||
|
||||
#include <memory>
|
||||
#include <utility>
|
||||
#include <type_traits>
|
||||
|
||||
#include "rclcpp/node_interfaces/node_topics_interface.hpp"
|
||||
|
||||
/// This header provides the get_node_topics_interface() template function.
|
||||
/**
|
||||
* This function is useful for getting the NodeTopicsInterface pointer from
|
||||
* various kinds of Node-like classes.
|
||||
*
|
||||
* It's able to get the NodeTopicsInterface pointer so long as the class
|
||||
* has a method called ``get_node_topics_interface()`` which returns
|
||||
* either a pointer (const or not) to a NodeTopicsInterface or a
|
||||
* std::shared_ptr to a NodeTopicsInterface.
|
||||
*/
|
||||
|
||||
namespace rclcpp
|
||||
{
|
||||
namespace node_interfaces
|
||||
{
|
||||
|
||||
namespace detail
|
||||
{
|
||||
|
||||
// This is a meta-programming checker for if a given Node-like object has a
|
||||
// getter called get_node_topics_interface() which returns various types,
|
||||
// e.g. const pointer or a shared pointer.
|
||||
template<typename NodeType, typename ReturnType>
|
||||
struct has_get_node_topics_interface
|
||||
{
|
||||
private:
|
||||
template<typename T>
|
||||
static constexpr
|
||||
auto
|
||||
check(T *)->typename std::is_same<
|
||||
decltype(std::declval<T>().get_node_topics_interface()),
|
||||
ReturnType
|
||||
>::type;
|
||||
|
||||
template<typename>
|
||||
static constexpr
|
||||
std::false_type
|
||||
check(...);
|
||||
|
||||
public:
|
||||
using type = decltype(check<NodeType>(nullptr));
|
||||
static constexpr bool value = type::value;
|
||||
};
|
||||
|
||||
// If NodeType is a pointer to NodeTopicsInterface already (just normal function overload).
|
||||
inline
|
||||
rclcpp::node_interfaces::NodeTopicsInterface *
|
||||
get_node_topics_interface_from_pointer(rclcpp::node_interfaces::NodeTopicsInterface * pointer)
|
||||
{
|
||||
return pointer;
|
||||
}
|
||||
|
||||
// If NodeType has a method called get_node_topics_interface() which returns a shared pointer.
|
||||
template<
|
||||
typename NodeType,
|
||||
typename std::enable_if<has_get_node_topics_interface<
|
||||
typename std::remove_pointer<NodeType>::type,
|
||||
std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>
|
||||
>::value, int>::type = 0
|
||||
>
|
||||
rclcpp::node_interfaces::NodeTopicsInterface *
|
||||
get_node_topics_interface_from_pointer(NodeType node_pointer)
|
||||
{
|
||||
return node_pointer->get_node_topics_interface().get();
|
||||
}
|
||||
|
||||
// If NodeType has a method called get_node_topics_interface() which returns a pointer.
|
||||
template<
|
||||
typename NodeType,
|
||||
typename std::enable_if<has_get_node_topics_interface<
|
||||
typename std::remove_pointer<NodeType>::type,
|
||||
rclcpp::node_interfaces::NodeTopicsInterface *
|
||||
>::value, int>::type = 0
|
||||
>
|
||||
rclcpp::node_interfaces::NodeTopicsInterface *
|
||||
get_node_topics_interface_from_pointer(NodeType node_pointer)
|
||||
{
|
||||
return node_pointer->get_node_topics_interface();
|
||||
}
|
||||
|
||||
// Forward shared_ptr's to const node pointer signatures.
|
||||
template<
|
||||
typename NodeType,
|
||||
typename std::enable_if<std::is_same<
|
||||
NodeType,
|
||||
typename std::shared_ptr<typename std::remove_pointer<NodeType>::type::element_type> *
|
||||
>::value, int>::type = 0
|
||||
>
|
||||
rclcpp::node_interfaces::NodeTopicsInterface *
|
||||
get_node_topics_interface_from_pointer(NodeType node_shared_pointer)
|
||||
{
|
||||
return get_node_topics_interface_from_pointer(node_shared_pointer->get());
|
||||
}
|
||||
|
||||
} // namespace detail
|
||||
|
||||
/// Get the NodeTopicsInterface as a pointer from a pointer to a "Node like" object.
|
||||
template<
|
||||
typename NodeType,
|
||||
typename std::enable_if<std::is_pointer<NodeType>::value, int>::type = 0
|
||||
>
|
||||
rclcpp::node_interfaces::NodeTopicsInterface *
|
||||
get_node_topics_interface(NodeType && node_pointer)
|
||||
{
|
||||
// Forward pointers to detail implmentation directly.
|
||||
return detail::get_node_topics_interface_from_pointer(std::forward<NodeType>(node_pointer));
|
||||
}
|
||||
|
||||
/// Get the NodeTopicsInterface as a pointer from a "Node like" object.
|
||||
template<
|
||||
typename NodeType,
|
||||
typename std::enable_if<!std::is_pointer<NodeType>::value, int>::type = 0
|
||||
>
|
||||
rclcpp::node_interfaces::NodeTopicsInterface *
|
||||
get_node_topics_interface(NodeType && node_reference)
|
||||
{
|
||||
// Forward references to detail implmentation as a pointer.
|
||||
return detail::get_node_topics_interface_from_pointer(&node_reference);
|
||||
}
|
||||
|
||||
} // namespace node_interfaces
|
||||
} // namespace rclcpp
|
||||
|
||||
#endif // RCLCPP__NODE_INTERFACES__GET_NODE_TOPICS_INTERFACE_HPP_
|
|
@ -19,10 +19,11 @@
|
|||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
#include "rcl/node.h"
|
||||
#include "rclcpp/context.hpp"
|
||||
#include "rclcpp/macros.hpp"
|
||||
#include "rclcpp/node_options.hpp"
|
||||
#include "rclcpp/node_interfaces/node_base_interface.hpp"
|
||||
#include "rclcpp/node_options.hpp"
|
||||
#include "rclcpp/visibility_control.hpp"
|
||||
|
||||
namespace rclcpp
|
||||
|
@ -34,13 +35,15 @@ namespace node_interfaces
|
|||
class NodeBase : public NodeBaseInterface
|
||||
{
|
||||
public:
|
||||
RCLCPP_SMART_PTR_ALIASES_ONLY(NodeBaseInterface)
|
||||
RCLCPP_SMART_PTR_ALIASES_ONLY(NodeBase)
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
NodeBase(
|
||||
const std::string & node_name,
|
||||
const std::string & namespace_,
|
||||
const NodeOptions & options);
|
||||
rclcpp::Context::SharedPtr context,
|
||||
const rcl_node_options_t & rcl_node_options,
|
||||
bool use_intra_process_default);
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
virtual
|
||||
|
@ -126,10 +129,16 @@ public:
|
|||
std::unique_lock<std::recursive_mutex>
|
||||
acquire_notify_guard_condition_lock() const;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
virtual
|
||||
bool
|
||||
get_use_intra_process_default() const;
|
||||
|
||||
private:
|
||||
RCLCPP_DISABLE_COPY(NodeBase)
|
||||
|
||||
rclcpp::Context::SharedPtr context_;
|
||||
bool use_intra_process_default_;
|
||||
|
||||
std::shared_ptr<rcl_node_t> node_handle_;
|
||||
|
||||
|
|
|
@ -155,6 +155,12 @@ public:
|
|||
virtual
|
||||
std::unique_lock<std::recursive_mutex>
|
||||
acquire_notify_guard_condition_lock() const = 0;
|
||||
|
||||
/// Return the default preference for using intra process communication.
|
||||
RCLCPP_PUBLIC
|
||||
virtual
|
||||
bool
|
||||
get_use_intra_process_default() const = 0;
|
||||
};
|
||||
|
||||
} // namespace node_interfaces
|
||||
|
|
|
@ -64,10 +64,10 @@ public:
|
|||
const node_interfaces::NodeServicesInterface::SharedPtr node_services,
|
||||
const node_interfaces::NodeClockInterface::SharedPtr node_clock,
|
||||
const std::vector<Parameter> & initial_parameters,
|
||||
bool use_intra_process,
|
||||
bool start_parameter_services,
|
||||
bool start_parameter_event_publisher,
|
||||
const rmw_qos_profile_t & parameter_event_qos_profile,
|
||||
const rclcpp::QoS & parameter_event_qos,
|
||||
const rclcpp::PublisherOptionsBase & parameter_event_publisher_options,
|
||||
bool allow_undeclared_parameters,
|
||||
bool automatically_declare_initial_parameters);
|
||||
|
||||
|
|
|
@ -42,45 +42,44 @@ public:
|
|||
explicit NodeTopics(rclcpp::node_interfaces::NodeBaseInterface * node_base);
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
virtual
|
||||
~NodeTopics();
|
||||
~NodeTopics() override;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
virtual
|
||||
rclcpp::PublisherBase::SharedPtr
|
||||
create_publisher(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::PublisherFactory & publisher_factory,
|
||||
rcl_publisher_options_t & publisher_options,
|
||||
bool use_intra_process);
|
||||
const rcl_publisher_options_t & publisher_options,
|
||||
bool use_intra_process) override;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
virtual
|
||||
void
|
||||
add_publisher(
|
||||
rclcpp::PublisherBase::SharedPtr publisher,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group);
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) override;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
virtual
|
||||
rclcpp::SubscriptionBase::SharedPtr
|
||||
create_subscription(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::SubscriptionFactory & subscription_factory,
|
||||
rcl_subscription_options_t & subscription_options,
|
||||
bool use_intra_process);
|
||||
const rcl_subscription_options_t & subscription_options,
|
||||
bool use_intra_process) override;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
virtual
|
||||
void
|
||||
add_subscription(
|
||||
rclcpp::SubscriptionBase::SharedPtr subscription,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group);
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) override;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
rclcpp::node_interfaces::NodeBaseInterface *
|
||||
get_node_base_interface() const override;
|
||||
|
||||
private:
|
||||
RCLCPP_DISABLE_COPY(NodeTopics)
|
||||
|
||||
NodeBaseInterface * node_base_;
|
||||
rclcpp::node_interfaces::NodeBaseInterface * node_base_;
|
||||
};
|
||||
|
||||
} // namespace node_interfaces
|
||||
|
|
|
@ -50,7 +50,7 @@ public:
|
|||
create_publisher(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::PublisherFactory & publisher_factory,
|
||||
rcl_publisher_options_t & publisher_options,
|
||||
const rcl_publisher_options_t & publisher_options,
|
||||
bool use_intra_process) = 0;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
|
@ -66,7 +66,7 @@ public:
|
|||
create_subscription(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::SubscriptionFactory & subscription_factory,
|
||||
rcl_subscription_options_t & subscription_options,
|
||||
const rcl_subscription_options_t & subscription_options,
|
||||
bool use_intra_process) = 0;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
|
@ -75,6 +75,11 @@ public:
|
|||
add_subscription(
|
||||
rclcpp::SubscriptionBase::SharedPtr subscription,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group) = 0;
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
virtual
|
||||
rclcpp::node_interfaces::NodeBaseInterface *
|
||||
get_node_base_interface() const = 0;
|
||||
};
|
||||
|
||||
} // namespace node_interfaces
|
||||
|
|
|
@ -23,6 +23,8 @@
|
|||
#include "rclcpp/context.hpp"
|
||||
#include "rclcpp/contexts/default_context.hpp"
|
||||
#include "rclcpp/parameter.hpp"
|
||||
#include "rclcpp/publisher_options.hpp"
|
||||
#include "rclcpp/qos.hpp"
|
||||
#include "rclcpp/visibility_control.hpp"
|
||||
|
||||
namespace rclcpp
|
||||
|
@ -43,7 +45,9 @@ public:
|
|||
* - use_intra_process_comms = false
|
||||
* - start_parameter_services = true
|
||||
* - start_parameter_event_publisher = true
|
||||
* - parameter_event_qos_profile = rmw_qos_profile_parameter_events
|
||||
* - parameter_event_qos = rclcpp::ParameterEventQoS
|
||||
* - with history setting and depth from rmw_qos_profile_parameter_events
|
||||
* - parameter_event_publisher_options = rclcpp::PublisherOptionsBase
|
||||
* - allow_undeclared_parameters = false
|
||||
* - automatically_declare_initial_parameters = false
|
||||
* - allocator = rcl_get_default_allocator()
|
||||
|
@ -202,18 +206,36 @@ public:
|
|||
NodeOptions &
|
||||
start_parameter_event_publisher(bool start_parameter_event_publisher);
|
||||
|
||||
/// Return a reference to the parameter_event_qos_profile QoS.
|
||||
/// Return a reference to the parameter_event_qos QoS.
|
||||
RCLCPP_PUBLIC
|
||||
const rmw_qos_profile_t &
|
||||
parameter_event_qos_profile() const;
|
||||
const rclcpp::QoS &
|
||||
parameter_event_qos() const;
|
||||
|
||||
/// Set the parameter_event_qos_profile QoS, return this for parameter idiom.
|
||||
/// Set the parameter_event_qos QoS, return this for parameter idiom.
|
||||
/**
|
||||
* The QoS settings to be used for the parameter event publisher, if enabled.
|
||||
*/
|
||||
RCLCPP_PUBLIC
|
||||
NodeOptions &
|
||||
parameter_event_qos_profile(const rmw_qos_profile_t & parameter_event_qos_profile);
|
||||
parameter_event_qos(const rclcpp::QoS & parameter_event_qos);
|
||||
|
||||
/// Return a reference to the parameter_event_publisher_options.
|
||||
RCLCPP_PUBLIC
|
||||
const rclcpp::PublisherOptionsBase &
|
||||
parameter_event_publisher_options() const;
|
||||
|
||||
/// Set the parameter_event_publisher_options, return this for parameter idiom.
|
||||
/**
|
||||
* The QoS settings to be used for the parameter event publisher, if enabled.
|
||||
*
|
||||
* \todo(wjwwood): make this take/store an instance of
|
||||
* rclcpp::PublisherOptionsWithAllocator<Allocator>, but to do that requires
|
||||
* NodeOptions to also be templated based on the Allocator type.
|
||||
*/
|
||||
RCLCPP_PUBLIC
|
||||
NodeOptions &
|
||||
parameter_event_publisher_options(
|
||||
const rclcpp::PublisherOptionsBase & parameter_event_publisher_options);
|
||||
|
||||
/// Return the allow_undeclared_parameters flag.
|
||||
RCLCPP_PUBLIC
|
||||
|
@ -290,7 +312,11 @@ private:
|
|||
|
||||
bool start_parameter_event_publisher_ {true};
|
||||
|
||||
rmw_qos_profile_t parameter_event_qos_profile_ {rmw_qos_profile_parameter_events};
|
||||
rclcpp::QoS parameter_event_qos_ = rclcpp::ParameterEventsQoS(
|
||||
rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)
|
||||
);
|
||||
|
||||
rclcpp::PublisherOptionsBase parameter_event_publisher_options_ = rclcpp::PublisherOptionsBase();
|
||||
|
||||
bool allow_undeclared_parameters_ {false};
|
||||
|
||||
|
|
|
@ -110,29 +110,23 @@ public:
|
|||
|
||||
template<
|
||||
typename CallbackT,
|
||||
typename Alloc = std::allocator<void>,
|
||||
typename SubscriptionT =
|
||||
rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent, Alloc>>
|
||||
typename AllocatorT = std::allocator<void>>
|
||||
typename rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
|
||||
on_parameter_event(CallbackT && callback)
|
||||
on_parameter_event(
|
||||
CallbackT && callback,
|
||||
const rclcpp::QoS & qos = (
|
||||
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default))
|
||||
),
|
||||
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
|
||||
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
|
||||
))
|
||||
{
|
||||
using rclcpp::message_memory_strategy::MessageMemoryStrategy;
|
||||
auto msg_mem_strat =
|
||||
MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent, Alloc>::create_default();
|
||||
|
||||
using rcl_interfaces::msg::ParameterEvent;
|
||||
return rclcpp::create_subscription<
|
||||
ParameterEvent, CallbackT, Alloc, ParameterEvent, SubscriptionT>(
|
||||
this->node_topics_interface_.get(),
|
||||
return rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
|
||||
this->node_topics_interface_,
|
||||
"parameter_events",
|
||||
qos,
|
||||
std::forward<CallbackT>(callback),
|
||||
rmw_qos_profile_default,
|
||||
SubscriptionEventCallbacks(),
|
||||
nullptr, // group,
|
||||
false, // ignore_local_publications,
|
||||
false, // use_intra_process_comms_,
|
||||
msg_mem_strat,
|
||||
std::make_shared<Alloc>());
|
||||
options);
|
||||
}
|
||||
|
||||
RCLCPP_PUBLIC
|
||||
|
@ -155,7 +149,7 @@ protected:
|
|||
wait_for_service_nanoseconds(std::chrono::nanoseconds timeout);
|
||||
|
||||
private:
|
||||
const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface_;
|
||||
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_interface_;
|
||||
rclcpp::Client<rcl_interfaces::srv::GetParameters>::SharedPtr get_parameters_client_;
|
||||
rclcpp::Client<rcl_interfaces::srv::GetParameterTypes>::SharedPtr
|
||||
get_parameter_types_client_;
|
||||
|
|
|
@ -49,7 +49,7 @@ struct PublisherFactory
|
|||
rclcpp::PublisherBase::SharedPtr(
|
||||
rclcpp::node_interfaces::NodeBaseInterface * node_base,
|
||||
const std::string & topic_name,
|
||||
rcl_publisher_options_t & publisher_options)>;
|
||||
const rcl_publisher_options_t & publisher_options)>;
|
||||
|
||||
PublisherFactoryFunction create_typed_publisher;
|
||||
};
|
||||
|
@ -68,15 +68,17 @@ create_publisher_factory(
|
|||
[event_callbacks, allocator](
|
||||
rclcpp::node_interfaces::NodeBaseInterface * node_base,
|
||||
const std::string & topic_name,
|
||||
rcl_publisher_options_t & publisher_options) -> std::shared_ptr<PublisherT>
|
||||
const rcl_publisher_options_t & publisher_options
|
||||
) -> std::shared_ptr<PublisherT>
|
||||
{
|
||||
auto options_copy = publisher_options;
|
||||
auto message_alloc = std::make_shared<typename PublisherT::MessageAlloc>(*allocator.get());
|
||||
publisher_options.allocator = allocator::get_rcl_allocator<MessageT>(*message_alloc.get());
|
||||
options_copy.allocator = allocator::get_rcl_allocator<MessageT>(*message_alloc.get());
|
||||
|
||||
return std::make_shared<PublisherT>(
|
||||
node_base,
|
||||
topic_name,
|
||||
publisher_options,
|
||||
options_copy,
|
||||
event_callbacks,
|
||||
message_alloc);
|
||||
};
|
||||
|
|
|
@ -21,24 +21,54 @@
|
|||
|
||||
#include "rclcpp/callback_group.hpp"
|
||||
#include "rclcpp/intra_process_setting.hpp"
|
||||
#include "rclcpp/qos.hpp"
|
||||
#include "rclcpp/qos_event.hpp"
|
||||
#include "rclcpp/visibility_control.hpp"
|
||||
#include "rcl/publisher.h"
|
||||
|
||||
namespace rclcpp
|
||||
{
|
||||
|
||||
/// Structure containing optional configuration for Publishers.
|
||||
template<typename Allocator>
|
||||
struct PublisherOptionsWithAllocator
|
||||
/// Non-templated part of PublisherOptionsWithAllocator<Allocator>.
|
||||
struct PublisherOptionsBase
|
||||
{
|
||||
PublisherEventCallbacks event_callbacks;
|
||||
/// The quality of service profile to pass on to the rmw implementation.
|
||||
rmw_qos_profile_t qos_profile = rmw_qos_profile_default;
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group;
|
||||
/// Optional custom allocator.
|
||||
std::shared_ptr<Allocator> allocator;
|
||||
/// Setting to explicitly set intraprocess communications.
|
||||
IntraProcessSetting use_intra_process_comm = IntraProcessSetting::NodeDefault;
|
||||
|
||||
/// Callbacks for various events related to publishers.
|
||||
PublisherEventCallbacks event_callbacks;
|
||||
|
||||
/// Callback group in which the waitable items from the publisher should be placed.
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group;
|
||||
};
|
||||
|
||||
/// Structure containing optional configuration for Publishers.
|
||||
template<typename Allocator>
|
||||
struct PublisherOptionsWithAllocator : public PublisherOptionsBase
|
||||
{
|
||||
/// Optional custom allocator.
|
||||
std::shared_ptr<Allocator> allocator = nullptr;
|
||||
|
||||
PublisherOptionsWithAllocator<Allocator>() {}
|
||||
|
||||
/// Constructor using base class as input.
|
||||
explicit PublisherOptionsWithAllocator(const PublisherOptionsBase & publisher_options_base)
|
||||
: PublisherOptionsBase(publisher_options_base)
|
||||
{}
|
||||
|
||||
/// Convert this class, and a rclcpp::QoS, into an rcl_publisher_options_t.
|
||||
template<typename MessageT>
|
||||
rcl_publisher_options_t
|
||||
to_rcl_publisher_options(const rclcpp::QoS & qos) const
|
||||
{
|
||||
rcl_publisher_options_t result;
|
||||
using AllocatorTraits = std::allocator_traits<Allocator>;
|
||||
using MessageAllocatorT = typename AllocatorTraits::template rebind_alloc<MessageT>;
|
||||
auto message_alloc = std::make_shared<MessageAllocatorT>(*allocator.get());
|
||||
result.allocator = allocator::get_rcl_allocator<MessageT>(*message_alloc);
|
||||
result.qos = qos.get_rmw_qos_profile();
|
||||
return result;
|
||||
}
|
||||
};
|
||||
|
||||
using PublisherOptions = PublisherOptionsWithAllocator<std::allocator<void>>;
|
||||
|
|
203
rclcpp/include/rclcpp/qos.hpp
Normal file
203
rclcpp/include/rclcpp/qos.hpp
Normal file
|
@ -0,0 +1,203 @@
|
|||
// 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.
|
||||
|
||||
#ifndef RCLCPP__QOS_HPP_
|
||||
#define RCLCPP__QOS_HPP_
|
||||
|
||||
#include <rmw/qos_profiles.h>
|
||||
#include <rmw/types.h>
|
||||
|
||||
#include "rclcpp/duration.hpp"
|
||||
#include "rclcpp/visibility_control.hpp"
|
||||
|
||||
namespace rclcpp
|
||||
{
|
||||
|
||||
/// QoS initialization values, cannot be created directly, use KeepAll or KeepLast instead.
|
||||
struct RCLCPP_PUBLIC QoSInitialization
|
||||
{
|
||||
rmw_qos_history_policy_t history_policy;
|
||||
size_t depth;
|
||||
|
||||
/// Constructor which takes both a history policy and a depth (even if it would be unused).
|
||||
QoSInitialization(rmw_qos_history_policy_t history_policy_arg, size_t depth_arg);
|
||||
|
||||
/// Create a QoSInitialization from an existing rmw_qos_profile_t, using its history and depth.
|
||||
static
|
||||
QoSInitialization
|
||||
from_rmw(const rmw_qos_profile_t & rmw_qos);
|
||||
};
|
||||
|
||||
/// Use to initialize the QoS with the keep_all history setting.
|
||||
struct RCLCPP_PUBLIC KeepAll : public rclcpp::QoSInitialization
|
||||
{
|
||||
KeepAll();
|
||||
};
|
||||
|
||||
/// Use to initialize the QoS with the keep_last history setting and the given depth.
|
||||
struct RCLCPP_PUBLIC KeepLast : public rclcpp::QoSInitialization
|
||||
{
|
||||
explicit KeepLast(size_t depth);
|
||||
};
|
||||
|
||||
/// Encapsulation of Quality of Service settings.
|
||||
class RCLCPP_PUBLIC QoS
|
||||
{
|
||||
public:
|
||||
/// Constructor which allows you to construct a QoS by giving the only required settings.
|
||||
explicit
|
||||
QoS(
|
||||
const QoSInitialization & qos_initialization,
|
||||
const rmw_qos_profile_t & initial_profile = rmw_qos_profile_default);
|
||||
|
||||
/// Conversion constructor to ease construction in the common case of just specifying depth.
|
||||
/**
|
||||
* Convenience constructor, equivalent to QoS(KeepLast(history_depth)).
|
||||
*/
|
||||
// cppcheck-suppress noExplicitConstructor
|
||||
QoS(size_t history_depth); // NOLINT(runtime/explicit): conversion constructor
|
||||
|
||||
/// Return the rmw qos profile.
|
||||
rmw_qos_profile_t &
|
||||
get_rmw_qos_profile();
|
||||
|
||||
/// Return the rmw qos profile.
|
||||
const rmw_qos_profile_t &
|
||||
get_rmw_qos_profile() const;
|
||||
|
||||
/// Set the history policy.
|
||||
QoS &
|
||||
history(rmw_qos_history_policy_t history);
|
||||
|
||||
/// Set the history to keep last.
|
||||
QoS &
|
||||
keep_last(size_t depth);
|
||||
|
||||
/// Set the history to keep all.
|
||||
QoS &
|
||||
keep_all();
|
||||
|
||||
/// Set the reliability setting.
|
||||
QoS &
|
||||
reliability(rmw_qos_reliability_policy_t reliability);
|
||||
|
||||
/// Set the reliability setting to reliable.
|
||||
QoS &
|
||||
reliable();
|
||||
|
||||
/// Set the reliability setting to best effort.
|
||||
QoS &
|
||||
best_effort();
|
||||
|
||||
/// Set the durability setting.
|
||||
QoS &
|
||||
durability(rmw_qos_durability_policy_t durability);
|
||||
|
||||
/// Set the durability setting to volatile.
|
||||
QoS &
|
||||
volitile();
|
||||
|
||||
/// Set the durability setting to transient local.
|
||||
QoS &
|
||||
transient_local();
|
||||
|
||||
/// Set the deadline setting.
|
||||
QoS &
|
||||
deadline(rmw_time_t deadline);
|
||||
|
||||
/// Set the deadline setting, rclcpp::Duration.
|
||||
QoS &
|
||||
deadline(const rclcpp::Duration & deadline);
|
||||
|
||||
/// Set the lifespan setting.
|
||||
QoS &
|
||||
lifespan(rmw_time_t lifespan);
|
||||
|
||||
/// Set the lifespan setting, rclcpp::Duration.
|
||||
QoS &
|
||||
lifespan(const rclcpp::Duration & lifespan);
|
||||
|
||||
/// Set the liveliness setting.
|
||||
QoS &
|
||||
liveliness(rmw_qos_liveliness_policy_t liveliness);
|
||||
|
||||
/// Set the liveliness_lease_duration setting.
|
||||
QoS &
|
||||
liveliness_lease_duration(rmw_time_t liveliness_lease_duration);
|
||||
|
||||
/// Set the liveliness_lease_duration setting, rclcpp::Duration.
|
||||
QoS &
|
||||
liveliness_lease_duration(const rclcpp::Duration & liveliness_lease_duration);
|
||||
|
||||
/// Set the avoid_ros_namespace_conventions setting.
|
||||
QoS &
|
||||
avoid_ros_namespace_conventions(bool avoid_ros_namespace_conventions);
|
||||
|
||||
private:
|
||||
rmw_qos_profile_t rmw_qos_profile_;
|
||||
};
|
||||
|
||||
class RCLCPP_PUBLIC SensorDataQoS : public QoS
|
||||
{
|
||||
public:
|
||||
explicit
|
||||
SensorDataQoS(
|
||||
const QoSInitialization & qos_initialization = (
|
||||
QoSInitialization::from_rmw(rmw_qos_profile_sensor_data)
|
||||
));
|
||||
};
|
||||
|
||||
class RCLCPP_PUBLIC ParametersQoS : public QoS
|
||||
{
|
||||
public:
|
||||
explicit
|
||||
ParametersQoS(
|
||||
const QoSInitialization & qos_initialization = (
|
||||
QoSInitialization::from_rmw(rmw_qos_profile_parameters)
|
||||
));
|
||||
};
|
||||
|
||||
class RCLCPP_PUBLIC ServicesQoS : public QoS
|
||||
{
|
||||
public:
|
||||
explicit
|
||||
ServicesQoS(
|
||||
const QoSInitialization & qos_initialization = (
|
||||
QoSInitialization::from_rmw(rmw_qos_profile_services_default)
|
||||
));
|
||||
};
|
||||
|
||||
class RCLCPP_PUBLIC ParameterEventsQoS : public QoS
|
||||
{
|
||||
public:
|
||||
explicit
|
||||
ParameterEventsQoS(
|
||||
const QoSInitialization & qos_initialization = (
|
||||
QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)
|
||||
));
|
||||
};
|
||||
|
||||
class RCLCPP_PUBLIC SystemDefaultsQoS : public QoS
|
||||
{
|
||||
public:
|
||||
explicit
|
||||
SystemDefaultsQoS(
|
||||
const QoSInitialization & qos_initialization = (
|
||||
QoSInitialization::from_rmw(rmw_qos_profile_system_default)
|
||||
));
|
||||
};
|
||||
|
||||
} // namespace rclcpp
|
||||
|
||||
#endif // RCLCPP__QOS_HPP_
|
|
@ -51,7 +51,7 @@ struct SubscriptionFactory
|
|||
rclcpp::SubscriptionBase::SharedPtr(
|
||||
rclcpp::node_interfaces::NodeBaseInterface * node_base,
|
||||
const std::string & topic_name,
|
||||
rcl_subscription_options_t & subscription_options)>;
|
||||
const rcl_subscription_options_t & subscription_options)>;
|
||||
|
||||
SubscriptionFactoryFunction create_typed_subscription;
|
||||
|
||||
|
@ -95,10 +95,11 @@ create_subscription_factory(
|
|||
[allocator, msg_mem_strat, any_subscription_callback, event_callbacks, message_alloc](
|
||||
rclcpp::node_interfaces::NodeBaseInterface * node_base,
|
||||
const std::string & topic_name,
|
||||
rcl_subscription_options_t & subscription_options
|
||||
const rcl_subscription_options_t & subscription_options
|
||||
) -> rclcpp::SubscriptionBase::SharedPtr
|
||||
{
|
||||
subscription_options.allocator =
|
||||
auto options_copy = subscription_options;
|
||||
options_copy.allocator =
|
||||
rclcpp::allocator::get_rcl_allocator<CallbackMessageT>(*message_alloc.get());
|
||||
|
||||
using rclcpp::Subscription;
|
||||
|
@ -108,7 +109,7 @@ create_subscription_factory(
|
|||
node_base->get_shared_rcl_node_handle(),
|
||||
*rosidl_typesupport_cpp::get_message_type_support_handle<MessageT>(),
|
||||
topic_name,
|
||||
subscription_options,
|
||||
options_copy,
|
||||
any_subscription_callback,
|
||||
event_callbacks,
|
||||
msg_mem_strat);
|
||||
|
|
|
@ -21,29 +21,57 @@
|
|||
|
||||
#include "rclcpp/callback_group.hpp"
|
||||
#include "rclcpp/intra_process_setting.hpp"
|
||||
#include "rclcpp/qos.hpp"
|
||||
#include "rclcpp/qos_event.hpp"
|
||||
#include "rclcpp/visibility_control.hpp"
|
||||
|
||||
namespace rclcpp
|
||||
{
|
||||
|
||||
/// Structure containing optional configuration for Subscriptions.
|
||||
template<typename Allocator>
|
||||
struct SubscriptionOptionsWithAllocator
|
||||
/// Non-template base class for subscription options.
|
||||
struct SubscriptionOptionsBase
|
||||
{
|
||||
/// Callbacks for events related to this subscription.
|
||||
SubscriptionEventCallbacks event_callbacks;
|
||||
/// The quality of service profile to pass on to the rmw implementation.
|
||||
rmw_qos_profile_t qos_profile = rmw_qos_profile_default;
|
||||
/// True to ignore local publications.
|
||||
bool ignore_local_publications = false;
|
||||
/// The callback group for this subscription. NULL to use the default callback group.
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group;
|
||||
/// Optional custom allocator.
|
||||
std::shared_ptr<Allocator> allocator;
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr callback_group = nullptr;
|
||||
/// Setting to explicitly set intraprocess communications.
|
||||
IntraProcessSetting use_intra_process_comm = IntraProcessSetting::NodeDefault;
|
||||
};
|
||||
|
||||
/// Structure containing optional configuration for Subscriptions.
|
||||
template<typename Allocator>
|
||||
struct SubscriptionOptionsWithAllocator : public SubscriptionOptionsBase
|
||||
{
|
||||
/// Optional custom allocator.
|
||||
std::shared_ptr<Allocator> allocator = nullptr;
|
||||
|
||||
SubscriptionOptionsWithAllocator<Allocator>() {}
|
||||
|
||||
/// Constructor using base class as input.
|
||||
explicit SubscriptionOptionsWithAllocator(
|
||||
const SubscriptionOptionsBase & subscription_options_base)
|
||||
: SubscriptionOptionsBase(subscription_options_base)
|
||||
{}
|
||||
|
||||
/// Convert this class, with a rclcpp::QoS, into an rcl_subscription_options_t.
|
||||
template<typename MessageT>
|
||||
rcl_subscription_options_t
|
||||
to_rcl_subscription_options(const rclcpp::QoS & qos) const
|
||||
{
|
||||
rcl_subscription_options_t result;
|
||||
using AllocatorTraits = std::allocator_traits<Allocator>;
|
||||
using MessageAllocatorT = typename AllocatorTraits::template rebind_alloc<MessageT>;
|
||||
auto message_alloc = std::make_shared<MessageAllocatorT>(*allocator.get());
|
||||
result.allocator = allocator::get_rcl_allocator<MessageT>(*message_alloc);
|
||||
result.ignore_local_publications = this->ignore_local_publications;
|
||||
result.qos = qos.get_rmw_qos_profile();
|
||||
return result;
|
||||
}
|
||||
};
|
||||
|
||||
using SubscriptionOptions = SubscriptionOptionsWithAllocator<std::allocator<void>>;
|
||||
|
||||
} // namespace rclcpp
|
||||
|
|
|
@ -18,9 +18,13 @@
|
|||
#include <memory>
|
||||
|
||||
#include "rclcpp/function_traits.hpp"
|
||||
#include "rcl/types.h"
|
||||
|
||||
namespace rclcpp
|
||||
{
|
||||
|
||||
class QoS;
|
||||
|
||||
namespace subscription_traits
|
||||
{
|
||||
|
||||
|
@ -69,7 +73,20 @@ template<typename MessageT, typename Deleter>
|
|||
struct extract_message_type<std::unique_ptr<MessageT, Deleter>>: extract_message_type<MessageT>
|
||||
{};
|
||||
|
||||
template<typename CallbackT>
|
||||
template<
|
||||
typename CallbackT,
|
||||
// Do not attempt if CallbackT is an integer (mistaken for depth)
|
||||
typename = std::enable_if_t<!std::is_integral<
|
||||
std::remove_cv_t<std::remove_reference_t<CallbackT>>>::value>,
|
||||
// Do not attempt if CallbackT is a QoS (mistaken for qos)
|
||||
typename = std::enable_if_t<!std::is_base_of<
|
||||
rclcpp::QoS,
|
||||
std::remove_cv_t<std::remove_reference_t<CallbackT>>>::value>,
|
||||
// Do not attempt if CallbackT is a rmw_qos_profile_t (mistaken for qos profile)
|
||||
typename = std::enable_if_t<!std::is_same<
|
||||
rmw_qos_profile_t,
|
||||
std::remove_cv_t<std::remove_reference_t<CallbackT>>>::value>
|
||||
>
|
||||
struct has_message_type : extract_message_type<
|
||||
typename rclcpp::function_traits::function_traits<CallbackT>::template argument_type<0>>
|
||||
{};
|
||||
|
|
|
@ -65,10 +65,6 @@ Duration::Duration(const rcl_duration_t & duration)
|
|||
// noop
|
||||
}
|
||||
|
||||
Duration::~Duration()
|
||||
{
|
||||
}
|
||||
|
||||
Duration::operator builtin_interfaces::msg::Duration() const
|
||||
{
|
||||
builtin_interfaces::msg::Duration msg_duration;
|
||||
|
@ -226,4 +222,15 @@ Duration::seconds() const
|
|||
return std::chrono::duration<double>(std::chrono::nanoseconds(rcl_duration_.nanoseconds)).count();
|
||||
}
|
||||
|
||||
rmw_time_t
|
||||
Duration::to_rmw_time() const
|
||||
{
|
||||
// reuse conversion logic from msg creation
|
||||
builtin_interfaces::msg::Duration msg = *this;
|
||||
rmw_time_t result;
|
||||
result.sec = msg.sec;
|
||||
result.nsec = msg.nanosec;
|
||||
return result;
|
||||
}
|
||||
|
||||
} // namespace rclcpp
|
||||
|
|
|
@ -109,7 +109,11 @@ Node::Node(
|
|||
const std::string & namespace_,
|
||||
const NodeOptions & options)
|
||||
: node_base_(new rclcpp::node_interfaces::NodeBase(
|
||||
node_name, namespace_, options)),
|
||||
node_name,
|
||||
namespace_,
|
||||
options.context(),
|
||||
*(options.get_rcl_node_options()),
|
||||
options.use_intra_process_comms())),
|
||||
node_graph_(new rclcpp::node_interfaces::NodeGraph(node_base_.get())),
|
||||
node_logging_(new rclcpp::node_interfaces::NodeLogging(node_base_.get())),
|
||||
node_timers_(new rclcpp::node_interfaces::NodeTimers(node_base_.get())),
|
||||
|
@ -129,10 +133,10 @@ Node::Node(
|
|||
node_services_,
|
||||
node_clock_,
|
||||
options.initial_parameters(),
|
||||
options.use_intra_process_comms(),
|
||||
options.start_parameter_services(),
|
||||
options.start_parameter_event_publisher(),
|
||||
options.parameter_event_qos_profile(),
|
||||
options.parameter_event_qos(),
|
||||
options.parameter_event_publisher_options(),
|
||||
options.allow_undeclared_parameters(),
|
||||
options.automatically_declare_initial_parameters()
|
||||
)),
|
||||
|
|
|
@ -32,8 +32,11 @@ using rclcpp::node_interfaces::NodeBase;
|
|||
NodeBase::NodeBase(
|
||||
const std::string & node_name,
|
||||
const std::string & namespace_,
|
||||
const rclcpp::NodeOptions & options)
|
||||
: context_(options.context()),
|
||||
rclcpp::Context::SharedPtr context,
|
||||
const rcl_node_options_t & rcl_node_options,
|
||||
bool use_intra_process_default)
|
||||
: context_(context),
|
||||
use_intra_process_default_(use_intra_process_default),
|
||||
node_handle_(nullptr),
|
||||
default_callback_group_(nullptr),
|
||||
associated_with_executor_(false),
|
||||
|
@ -42,7 +45,7 @@ NodeBase::NodeBase(
|
|||
// Setup the guard condition that is notified when changes occur in the graph.
|
||||
rcl_guard_condition_options_t guard_condition_options = rcl_guard_condition_get_default_options();
|
||||
rcl_ret_t ret = rcl_guard_condition_init(
|
||||
¬ify_guard_condition_, options.context()->get_rcl_context().get(), guard_condition_options);
|
||||
¬ify_guard_condition_, context_->get_rcl_context().get(), guard_condition_options);
|
||||
if (ret != RCL_RET_OK) {
|
||||
throw_from_rcl_error(ret, "failed to create interrupt guard condition");
|
||||
}
|
||||
|
@ -63,7 +66,7 @@ NodeBase::NodeBase(
|
|||
ret = rcl_node_init(
|
||||
rcl_node.get(),
|
||||
node_name.c_str(), namespace_.c_str(),
|
||||
options.context()->get_rcl_context().get(), options.get_rcl_node_options());
|
||||
context_->get_rcl_context().get(), &rcl_node_options);
|
||||
if (ret != RCL_RET_OK) {
|
||||
// Finalize the interrupt guard condition.
|
||||
finalize_notify_guard_condition();
|
||||
|
@ -259,3 +262,9 @@ NodeBase::acquire_notify_guard_condition_lock() const
|
|||
{
|
||||
return std::unique_lock<std::recursive_mutex>(notify_guard_condition_mutex_);
|
||||
}
|
||||
|
||||
bool
|
||||
NodeBase::get_use_intra_process_default() const
|
||||
{
|
||||
return use_intra_process_default_;
|
||||
}
|
||||
|
|
|
@ -45,14 +45,14 @@ using rclcpp::node_interfaces::NodeParameters;
|
|||
NodeParameters::NodeParameters(
|
||||
const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
|
||||
const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
|
||||
const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics,
|
||||
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics,
|
||||
const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services,
|
||||
const rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock,
|
||||
const std::vector<rclcpp::Parameter> & initial_parameters,
|
||||
bool use_intra_process,
|
||||
bool start_parameter_services,
|
||||
bool start_parameter_event_publisher,
|
||||
const rmw_qos_profile_t & parameter_event_qos_profile,
|
||||
const rclcpp::QoS & parameter_event_qos,
|
||||
const rclcpp::PublisherOptionsBase & parameter_event_publisher_options,
|
||||
bool allow_undeclared_parameters,
|
||||
bool automatically_declare_initial_parameters)
|
||||
: allow_undeclared_(allow_undeclared_parameters),
|
||||
|
@ -64,7 +64,9 @@ NodeParameters::NodeParameters(
|
|||
using PublisherT = rclcpp::Publisher<MessageT>;
|
||||
using AllocatorT = std::allocator<void>;
|
||||
// TODO(wjwwood): expose this allocator through the Parameter interface.
|
||||
auto allocator = std::make_shared<AllocatorT>();
|
||||
rclcpp::PublisherOptionsWithAllocator<AllocatorT> publisher_options(
|
||||
parameter_event_publisher_options);
|
||||
publisher_options.allocator = std::make_shared<AllocatorT>();
|
||||
|
||||
if (start_parameter_services) {
|
||||
parameter_service_ = std::make_shared<ParameterService>(node_base, node_services, this);
|
||||
|
@ -72,13 +74,10 @@ NodeParameters::NodeParameters(
|
|||
|
||||
if (start_parameter_event_publisher) {
|
||||
events_publisher_ = rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
|
||||
node_topics.get(),
|
||||
node_topics,
|
||||
"parameter_events",
|
||||
parameter_event_qos_profile,
|
||||
PublisherEventCallbacks(),
|
||||
nullptr,
|
||||
use_intra_process,
|
||||
allocator);
|
||||
parameter_event_qos,
|
||||
publisher_options);
|
||||
}
|
||||
|
||||
// Get the node options
|
||||
|
|
|
@ -34,7 +34,7 @@ rclcpp::PublisherBase::SharedPtr
|
|||
NodeTopics::create_publisher(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::PublisherFactory & publisher_factory,
|
||||
rcl_publisher_options_t & publisher_options,
|
||||
const rcl_publisher_options_t & publisher_options,
|
||||
bool use_intra_process)
|
||||
{
|
||||
// Create the MessageT specific Publisher using the factory, but store it as PublisherBase.
|
||||
|
@ -91,7 +91,7 @@ rclcpp::SubscriptionBase::SharedPtr
|
|||
NodeTopics::create_subscription(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::SubscriptionFactory & subscription_factory,
|
||||
rcl_subscription_options_t & subscription_options,
|
||||
const rcl_subscription_options_t & subscription_options,
|
||||
bool use_intra_process)
|
||||
{
|
||||
auto subscription = subscription_factory.create_typed_subscription(
|
||||
|
@ -103,8 +103,9 @@ NodeTopics::create_subscription(
|
|||
auto ipm =
|
||||
context->get_sub_context<rclcpp::intra_process_manager::IntraProcessManager>();
|
||||
uint64_t intra_process_subscription_id = ipm->add_subscription(subscription);
|
||||
subscription_options.ignore_local_publications = false;
|
||||
subscription->setup_intra_process(intra_process_subscription_id, ipm, subscription_options);
|
||||
auto options_copy = subscription_options;
|
||||
options_copy.ignore_local_publications = false;
|
||||
subscription->setup_intra_process(intra_process_subscription_id, ipm, options_copy);
|
||||
}
|
||||
|
||||
// Return the completed subscription.
|
||||
|
@ -142,3 +143,9 @@ NodeTopics::add_subscription(
|
|||
}
|
||||
}
|
||||
}
|
||||
|
||||
rclcpp::node_interfaces::NodeBaseInterface *
|
||||
NodeTopics::get_node_base_interface() const
|
||||
{
|
||||
return node_base_;
|
||||
}
|
||||
|
|
|
@ -21,6 +21,8 @@
|
|||
|
||||
#include "rclcpp/exceptions.hpp"
|
||||
#include "rclcpp/logging.hpp"
|
||||
#include "rclcpp/publisher_options.hpp"
|
||||
#include "rclcpp/qos.hpp"
|
||||
|
||||
using rclcpp::exceptions::throw_from_rcl_error;
|
||||
|
||||
|
@ -208,16 +210,30 @@ NodeOptions::start_parameter_event_publisher(bool start_parameter_event_publishe
|
|||
return *this;
|
||||
}
|
||||
|
||||
const rmw_qos_profile_t &
|
||||
NodeOptions::parameter_event_qos_profile() const
|
||||
const rclcpp::QoS &
|
||||
NodeOptions::parameter_event_qos() const
|
||||
{
|
||||
return this->parameter_event_qos_profile_;
|
||||
return this->parameter_event_qos_;
|
||||
}
|
||||
|
||||
NodeOptions &
|
||||
NodeOptions::parameter_event_qos_profile(const rmw_qos_profile_t & parameter_event_qos_profile)
|
||||
NodeOptions::parameter_event_qos(const rclcpp::QoS & parameter_event_qos)
|
||||
{
|
||||
this->parameter_event_qos_profile_ = parameter_event_qos_profile;
|
||||
this->parameter_event_qos_ = parameter_event_qos;
|
||||
return *this;
|
||||
}
|
||||
|
||||
const rclcpp::PublisherOptionsBase &
|
||||
NodeOptions::parameter_event_publisher_options() const
|
||||
{
|
||||
return parameter_event_publisher_options_;
|
||||
}
|
||||
|
||||
NodeOptions &
|
||||
NodeOptions::parameter_event_publisher_options(
|
||||
const rclcpp::PublisherOptionsBase & parameter_event_publisher_options)
|
||||
{
|
||||
parameter_event_publisher_options_ = parameter_event_publisher_options;
|
||||
return *this;
|
||||
}
|
||||
|
||||
|
|
207
rclcpp/src/rclcpp/qos.cpp
Normal file
207
rclcpp/src/rclcpp/qos.cpp
Normal file
|
@ -0,0 +1,207 @@
|
|||
// 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 "rclcpp/qos.hpp"
|
||||
|
||||
#include <rmw/types.h>
|
||||
|
||||
namespace rclcpp
|
||||
{
|
||||
|
||||
QoSInitialization::QoSInitialization(rmw_qos_history_policy_t history_policy_arg, size_t depth_arg)
|
||||
: history_policy(history_policy_arg), depth(depth_arg)
|
||||
{}
|
||||
|
||||
QoSInitialization
|
||||
QoSInitialization::from_rmw(const rmw_qos_profile_t & rmw_qos)
|
||||
{
|
||||
switch (rmw_qos.history) {
|
||||
case RMW_QOS_POLICY_HISTORY_KEEP_ALL:
|
||||
return KeepAll();
|
||||
case RMW_QOS_POLICY_HISTORY_KEEP_LAST:
|
||||
case RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT:
|
||||
case RMW_QOS_POLICY_HISTORY_UNKNOWN:
|
||||
default:
|
||||
return KeepLast(rmw_qos.depth);
|
||||
}
|
||||
}
|
||||
|
||||
KeepAll::KeepAll()
|
||||
: QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_ALL, 0)
|
||||
{}
|
||||
|
||||
KeepLast::KeepLast(size_t depth)
|
||||
: QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_LAST, depth)
|
||||
{}
|
||||
|
||||
QoS::QoS(
|
||||
const QoSInitialization & qos_initialization,
|
||||
const rmw_qos_profile_t & initial_profile)
|
||||
: rmw_qos_profile_(initial_profile)
|
||||
{
|
||||
rmw_qos_profile_.history = qos_initialization.history_policy;
|
||||
rmw_qos_profile_.depth = qos_initialization.depth;
|
||||
}
|
||||
|
||||
QoS::QoS(size_t history_depth)
|
||||
: QoS(KeepLast(history_depth))
|
||||
{}
|
||||
|
||||
rmw_qos_profile_t &
|
||||
QoS::get_rmw_qos_profile()
|
||||
{
|
||||
return rmw_qos_profile_;
|
||||
}
|
||||
|
||||
const rmw_qos_profile_t &
|
||||
QoS::get_rmw_qos_profile() const
|
||||
{
|
||||
return rmw_qos_profile_;
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::history(rmw_qos_history_policy_t history)
|
||||
{
|
||||
rmw_qos_profile_.history = history;
|
||||
return *this;
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::keep_last(size_t depth)
|
||||
{
|
||||
rmw_qos_profile_.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
|
||||
rmw_qos_profile_.depth = depth;
|
||||
return *this;
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::keep_all()
|
||||
{
|
||||
rmw_qos_profile_.history = RMW_QOS_POLICY_HISTORY_KEEP_ALL;
|
||||
rmw_qos_profile_.depth = 0;
|
||||
return *this;
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::reliability(rmw_qos_reliability_policy_t reliability)
|
||||
{
|
||||
rmw_qos_profile_.reliability = reliability;
|
||||
return *this;
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::reliable()
|
||||
{
|
||||
return this->reliability(RMW_QOS_POLICY_RELIABILITY_RELIABLE);
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::best_effort()
|
||||
{
|
||||
return this->reliability(RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT);
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::durability(rmw_qos_durability_policy_t durability)
|
||||
{
|
||||
rmw_qos_profile_.durability = durability;
|
||||
return *this;
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::volitile()
|
||||
{
|
||||
return this->durability(RMW_QOS_POLICY_DURABILITY_VOLATILE);
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::transient_local()
|
||||
{
|
||||
return this->durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::deadline(rmw_time_t deadline)
|
||||
{
|
||||
rmw_qos_profile_.deadline = deadline;
|
||||
return *this;
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::deadline(const rclcpp::Duration & deadline)
|
||||
{
|
||||
return this->deadline(deadline.to_rmw_time());
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::lifespan(rmw_time_t lifespan)
|
||||
{
|
||||
rmw_qos_profile_.lifespan = lifespan;
|
||||
return *this;
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::lifespan(const rclcpp::Duration & lifespan)
|
||||
{
|
||||
return this->lifespan(lifespan.to_rmw_time());
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::liveliness(rmw_qos_liveliness_policy_t liveliness)
|
||||
{
|
||||
rmw_qos_profile_.liveliness = liveliness;
|
||||
return *this;
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::liveliness_lease_duration(rmw_time_t liveliness_lease_duration)
|
||||
{
|
||||
rmw_qos_profile_.liveliness_lease_duration = liveliness_lease_duration;
|
||||
return *this;
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::liveliness_lease_duration(const rclcpp::Duration & liveliness_lease_duration)
|
||||
{
|
||||
return this->liveliness_lease_duration(liveliness_lease_duration.to_rmw_time());
|
||||
}
|
||||
|
||||
QoS &
|
||||
QoS::avoid_ros_namespace_conventions(bool avoid_ros_namespace_conventions)
|
||||
{
|
||||
rmw_qos_profile_.avoid_ros_namespace_conventions = avoid_ros_namespace_conventions;
|
||||
return *this;
|
||||
}
|
||||
|
||||
SensorDataQoS::SensorDataQoS(const QoSInitialization & qos_initialization)
|
||||
: QoS(qos_initialization, rmw_qos_profile_sensor_data)
|
||||
{}
|
||||
|
||||
ParametersQoS::ParametersQoS(const QoSInitialization & qos_initialization)
|
||||
: QoS(qos_initialization, rmw_qos_profile_parameters)
|
||||
{}
|
||||
|
||||
ServicesQoS::ServicesQoS(const QoSInitialization & qos_initialization)
|
||||
: QoS(qos_initialization, rmw_qos_profile_services_default)
|
||||
{}
|
||||
|
||||
ParameterEventsQoS::ParameterEventsQoS(const QoSInitialization & qos_initialization)
|
||||
: QoS(qos_initialization, rmw_qos_profile_parameter_events)
|
||||
{}
|
||||
|
||||
SystemDefaultsQoS::SystemDefaultsQoS(const QoSInitialization & qos_initialization)
|
||||
: QoS(qos_initialization, rmw_qos_profile_system_default)
|
||||
{}
|
||||
|
||||
} // namespace rclcpp
|
|
@ -28,7 +28,6 @@
|
|||
#include "rclcpp/time.hpp"
|
||||
#include "rclcpp/time_source.hpp"
|
||||
|
||||
|
||||
namespace rclcpp
|
||||
{
|
||||
|
||||
|
@ -208,27 +207,13 @@ void TimeSource::create_clock_sub()
|
|||
// Subscription already created.
|
||||
return;
|
||||
}
|
||||
const std::string topic_name = "/clock";
|
||||
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group;
|
||||
using rclcpp::message_memory_strategy::MessageMemoryStrategy;
|
||||
auto msg_mem_strat = MessageMemoryStrategy<MessageT, Alloc>::create_default();
|
||||
auto allocator = std::make_shared<Alloc>();
|
||||
auto cb = std::bind(&TimeSource::clock_cb, this, std::placeholders::_1);
|
||||
|
||||
clock_subscription_ = rclcpp::create_subscription<
|
||||
MessageT, decltype(cb), Alloc, MessageT, SubscriptionT
|
||||
>(
|
||||
node_topics_.get(),
|
||||
topic_name,
|
||||
std::move(cb),
|
||||
rmw_qos_profile_default,
|
||||
rclcpp::SubscriptionEventCallbacks(),
|
||||
group,
|
||||
false,
|
||||
false,
|
||||
msg_mem_strat,
|
||||
allocator);
|
||||
clock_subscription_ = rclcpp::create_subscription<rosgraph_msgs::msg::Clock>(
|
||||
node_topics_,
|
||||
"/clock",
|
||||
rclcpp::QoS(QoSInitialization::from_rmw(rmw_qos_profile_default)),
|
||||
std::bind(&TimeSource::clock_cb, this, std::placeholders::_1)
|
||||
);
|
||||
}
|
||||
|
||||
void TimeSource::destroy_clock_sub()
|
||||
|
|
64
rclcpp/test/node_interfaces/node_wrapper.hpp
Normal file
64
rclcpp/test/node_interfaces/node_wrapper.hpp
Normal file
|
@ -0,0 +1,64 @@
|
|||
// 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.
|
||||
|
||||
#ifndef NODE_INTERFACES__NODE_WRAPPER_HPP_
|
||||
#define NODE_INTERFACES__NODE_WRAPPER_HPP_
|
||||
|
||||
#include <memory>
|
||||
#include <string>
|
||||
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
|
||||
class NodeWrapper
|
||||
{
|
||||
public:
|
||||
explicit NodeWrapper(const std::string & name)
|
||||
: node(std::make_shared<rclcpp::Node>(name))
|
||||
{}
|
||||
|
||||
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr
|
||||
get_node_base_interface() {return this->node->get_node_base_interface();}
|
||||
|
||||
rclcpp::node_interfaces::NodeClockInterface::SharedPtr
|
||||
get_node_clock_interface() {return this->node->get_node_clock_interface();}
|
||||
|
||||
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr
|
||||
get_node_graph_interface() {return this->node->get_node_graph_interface();}
|
||||
|
||||
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr
|
||||
get_node_logging_interface() {return this->node->get_node_logging_interface();}
|
||||
|
||||
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr
|
||||
get_node_timers_interface() {return this->node->get_node_timers_interface();}
|
||||
|
||||
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr
|
||||
get_node_topics_interface() {return this->node->get_node_topics_interface();}
|
||||
|
||||
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr
|
||||
get_node_services_interface() {return this->node->get_node_services_interface();}
|
||||
|
||||
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
|
||||
get_node_waitables_interface() {return this->node->get_node_waitables_interface();}
|
||||
|
||||
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr
|
||||
get_node_parameters_interface() {return this->node->get_node_parameters_interface();}
|
||||
|
||||
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr
|
||||
get_node_time_source_interface() {return this->node->get_node_time_source_interface();}
|
||||
|
||||
private:
|
||||
rclcpp::Node::SharedPtr node;
|
||||
};
|
||||
|
||||
#endif // NODE_INTERFACES__NODE_WRAPPER_HPP_
|
|
@ -0,0 +1,28 @@
|
|||
// 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 <memory>
|
||||
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include "rclcpp/node_interfaces/get_node_topics_interface.hpp"
|
||||
|
||||
int main(void)
|
||||
{
|
||||
auto node = std::make_shared<rclcpp::Node>("test_node");
|
||||
std::shared_ptr<const rclcpp::Node> const_node_ptr = node;
|
||||
// Should fail because a const node cannot have a non-const method called on it.
|
||||
rclcpp::node_interfaces::NodeTopicsInterface * result =
|
||||
rclcpp::node_interfaces::get_node_topics_interface(const_node_ptr);
|
||||
(void)result;
|
||||
}
|
|
@ -0,0 +1,30 @@
|
|||
// 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 <memory>
|
||||
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include "rclcpp/node_interfaces/get_node_topics_interface.hpp"
|
||||
|
||||
#include "../node_wrapper.hpp"
|
||||
|
||||
int main(void)
|
||||
{
|
||||
auto node = std::make_shared<NodeWrapper>("test_wrapped_node");
|
||||
std::shared_ptr<const NodeWrapper> const_node_ptr = node;
|
||||
// Should fail because a const node cannot have a non-const method called on it.
|
||||
rclcpp::node_interfaces::NodeTopicsInterface * result =
|
||||
rclcpp::node_interfaces::get_node_topics_interface(const_node_ptr);
|
||||
(void)result;
|
||||
}
|
|
@ -0,0 +1,28 @@
|
|||
// 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 <memory>
|
||||
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include "rclcpp/node_interfaces/get_node_topics_interface.hpp"
|
||||
|
||||
int main(void)
|
||||
{
|
||||
auto node = std::make_shared<rclcpp::Node>("test_node");
|
||||
const rclcpp::Node & const_node_reference = *node;
|
||||
// Should fail because a const node cannot have a non-const method called on it.
|
||||
rclcpp::node_interfaces::NodeTopicsInterface * result =
|
||||
rclcpp::node_interfaces::get_node_topics_interface(const_node_reference);
|
||||
(void)result;
|
||||
}
|
|
@ -0,0 +1,30 @@
|
|||
// 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 <memory>
|
||||
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
#include "rclcpp/node_interfaces/get_node_topics_interface.hpp"
|
||||
|
||||
#include "../node_wrapper.hpp"
|
||||
|
||||
int main(void)
|
||||
{
|
||||
auto node = std::make_shared<NodeWrapper>("test_wrapped_node");
|
||||
const NodeWrapper & const_node_reference = *node;
|
||||
// Should fail because a const node cannot have a non-const method called on it.
|
||||
rclcpp::node_interfaces::NodeTopicsInterface * result =
|
||||
rclcpp::node_interfaces::get_node_topics_interface(const_node_reference);
|
||||
(void)result;
|
||||
}
|
97
rclcpp/test/node_interfaces/test_get_node_interfaces.cpp
Normal file
97
rclcpp/test/node_interfaces/test_get_node_interfaces.cpp
Normal file
|
@ -0,0 +1,97 @@
|
|||
// 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 <memory>
|
||||
#include <string>
|
||||
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
#include "rclcpp/node_interfaces/get_node_topics_interface.hpp"
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
|
||||
#include "./node_wrapper.hpp"
|
||||
|
||||
static const std::string node_suffix = "test_get_node_interfaces"; // NOLINT
|
||||
|
||||
class TestGetNodeInterfaces : public ::testing::Test
|
||||
{
|
||||
protected:
|
||||
static void SetUpTestCase()
|
||||
{
|
||||
rclcpp::init(0, nullptr);
|
||||
node = std::make_shared<rclcpp::Node>(node_suffix);
|
||||
wrapped_node = std::make_shared<NodeWrapper>("wrapped_" + node_suffix);
|
||||
}
|
||||
|
||||
static void TearDownTestCase()
|
||||
{
|
||||
node.reset();
|
||||
wrapped_node.reset();
|
||||
}
|
||||
|
||||
static rclcpp::Node::SharedPtr node;
|
||||
static std::shared_ptr<NodeWrapper> wrapped_node;
|
||||
};
|
||||
|
||||
rclcpp::Node::SharedPtr TestGetNodeInterfaces::node = nullptr;
|
||||
std::shared_ptr<NodeWrapper> TestGetNodeInterfaces::wrapped_node = nullptr;
|
||||
|
||||
TEST_F(TestGetNodeInterfaces, rclcpp_node_shared_ptr) {
|
||||
auto result = rclcpp::node_interfaces::get_node_topics_interface(this->node);
|
||||
static_assert(
|
||||
std::is_same<
|
||||
rclcpp::node_interfaces::NodeTopicsInterface *,
|
||||
decltype(result)
|
||||
>::value, "expected rclcpp::node_interfaces::NodeTopicsInterface *");
|
||||
}
|
||||
|
||||
TEST_F(TestGetNodeInterfaces, node_shared_ptr) {
|
||||
auto result = rclcpp::node_interfaces::get_node_topics_interface(this->wrapped_node);
|
||||
static_assert(
|
||||
std::is_same<
|
||||
rclcpp::node_interfaces::NodeTopicsInterface *,
|
||||
decltype(result)
|
||||
>::value, "expected rclcpp::node_interfaces::NodeTopicsInterface *");
|
||||
}
|
||||
|
||||
TEST_F(TestGetNodeInterfaces, rclcpp_node_reference) {
|
||||
rclcpp::Node & node_reference = *this->node;
|
||||
auto result = rclcpp::node_interfaces::get_node_topics_interface(node_reference);
|
||||
static_assert(
|
||||
std::is_same<
|
||||
rclcpp::node_interfaces::NodeTopicsInterface *,
|
||||
decltype(result)
|
||||
>::value, "expected rclcpp::node_interfaces::NodeTopicsInterface *");
|
||||
}
|
||||
|
||||
TEST_F(TestGetNodeInterfaces, node_reference) {
|
||||
NodeWrapper & wrapped_node_reference = *this->wrapped_node;
|
||||
auto result = rclcpp::node_interfaces::get_node_topics_interface(wrapped_node_reference);
|
||||
static_assert(
|
||||
std::is_same<
|
||||
rclcpp::node_interfaces::NodeTopicsInterface *,
|
||||
decltype(result)
|
||||
>::value, "expected rclcpp::node_interfaces::NodeTopicsInterface *");
|
||||
}
|
||||
|
||||
TEST_F(TestGetNodeInterfaces, interface_shared_pointer) {
|
||||
std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface> interface_shared_ptr =
|
||||
this->node->get_node_topics_interface();
|
||||
auto result = rclcpp::node_interfaces::get_node_topics_interface(interface_shared_ptr);
|
||||
static_assert(
|
||||
std::is_same<
|
||||
rclcpp::node_interfaces::NodeTopicsInterface *,
|
||||
decltype(result)
|
||||
>::value, "expected rclcpp::node_interfaces::NodeTopicsInterface *");
|
||||
}
|
|
@ -60,6 +60,7 @@ TEST(TestDuration, operators) {
|
|||
rclcpp::Duration time = rclcpp::Duration(0, 0);
|
||||
rclcpp::Duration copy_constructor_duration(time);
|
||||
rclcpp::Duration assignment_op_duration = rclcpp::Duration(1, 0);
|
||||
(void)assignment_op_duration;
|
||||
assignment_op_duration = time;
|
||||
|
||||
EXPECT_TRUE(time == copy_constructor_duration);
|
||||
|
@ -75,6 +76,14 @@ TEST(TestDuration, chrono_overloads) {
|
|||
EXPECT_EQ(d1, d2);
|
||||
EXPECT_EQ(d1, d3);
|
||||
EXPECT_EQ(d2, d3);
|
||||
|
||||
// check non-nanosecond durations
|
||||
std::chrono::milliseconds chrono_ms(100);
|
||||
auto d4 = rclcpp::Duration(chrono_ms);
|
||||
EXPECT_EQ(chrono_ms, d4.to_chrono<std::chrono::nanoseconds>());
|
||||
std::chrono::duration<double, std::chrono::seconds::period> chrono_float_seconds(3.14);
|
||||
auto d5 = rclcpp::Duration(chrono_float_seconds);
|
||||
EXPECT_EQ(chrono_float_seconds, d5.to_chrono<decltype(chrono_float_seconds)>());
|
||||
}
|
||||
|
||||
TEST(TestDuration, overflows) {
|
||||
|
|
|
@ -1,70 +0,0 @@
|
|||
// 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 "test_msgs/msg/empty.hpp"
|
||||
|
||||
class TestPubSubOptionAPI : public ::testing::Test
|
||||
{
|
||||
protected:
|
||||
static void SetUpTestCase()
|
||||
{
|
||||
rclcpp::init(0, nullptr);
|
||||
}
|
||||
|
||||
void SetUp()
|
||||
{
|
||||
node = std::make_shared<rclcpp::Node>("my_node", "/ns");
|
||||
}
|
||||
|
||||
void TearDown()
|
||||
{
|
||||
node.reset();
|
||||
}
|
||||
|
||||
rclcpp::Node::SharedPtr node;
|
||||
};
|
||||
|
||||
TEST_F(TestPubSubOptionAPI, check_for_ambiguous) {
|
||||
rclcpp::PublisherOptions pub_options;
|
||||
rclcpp::SubscriptionOptions sub_options;
|
||||
|
||||
auto topic_only_pub = node->create_publisher<test_msgs::msg::Empty>(
|
||||
"topic_only");
|
||||
auto topic_depth_pub = node->create_publisher<test_msgs::msg::Empty>(
|
||||
"topic_depth",
|
||||
10);
|
||||
auto all_options_pub = node->create_publisher<test_msgs::msg::Empty>(
|
||||
"topic_options",
|
||||
10,
|
||||
pub_options);
|
||||
|
||||
auto topic_only_sub = node->create_subscription<test_msgs::msg::Empty>(
|
||||
"topic_only",
|
||||
[](std::shared_ptr<test_msgs::msg::Empty>) {});
|
||||
auto topic_depth_sub = node->create_subscription<test_msgs::msg::Empty>(
|
||||
"topic_depth",
|
||||
[](std::shared_ptr<test_msgs::msg::Empty>) {},
|
||||
10);
|
||||
auto all_options_sub = node->create_subscription<test_msgs::msg::Empty>(
|
||||
"topic_options",
|
||||
[](std::shared_ptr<test_msgs::msg::Empty>) {},
|
||||
10,
|
||||
sub_options);
|
||||
}
|
|
@ -80,16 +80,88 @@ TEST_F(TestPublisher, construction_and_destruction) {
|
|||
initialize();
|
||||
using rcl_interfaces::msg::IntraProcessMessage;
|
||||
{
|
||||
auto publisher = node->create_publisher<IntraProcessMessage>("topic");
|
||||
auto publisher = node->create_publisher<IntraProcessMessage>("topic", 42);
|
||||
(void)publisher;
|
||||
}
|
||||
|
||||
{
|
||||
ASSERT_THROW({
|
||||
auto publisher = node->create_publisher<IntraProcessMessage>("invalid_topic?");
|
||||
auto publisher = node->create_publisher<IntraProcessMessage>("invalid_topic?", 42);
|
||||
}, rclcpp::exceptions::InvalidTopicNameError);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
Testing publisher creation signatures.
|
||||
*/
|
||||
TEST_F(TestPublisher, various_creation_signatures) {
|
||||
initialize();
|
||||
using rcl_interfaces::msg::IntraProcessMessage;
|
||||
{
|
||||
auto publisher = node->create_publisher<IntraProcessMessage>("topic", 42);
|
||||
(void)publisher;
|
||||
}
|
||||
{
|
||||
auto publisher = node->create_publisher<IntraProcessMessage>("topic", rclcpp::QoS(42));
|
||||
(void)publisher;
|
||||
}
|
||||
{
|
||||
auto publisher =
|
||||
node->create_publisher<IntraProcessMessage>("topic", rclcpp::QoS(rclcpp::KeepLast(42)));
|
||||
(void)publisher;
|
||||
}
|
||||
{
|
||||
auto publisher =
|
||||
node->create_publisher<IntraProcessMessage>("topic", rclcpp::QoS(rclcpp::KeepAll()));
|
||||
(void)publisher;
|
||||
}
|
||||
{
|
||||
auto publisher =
|
||||
node->create_publisher<IntraProcessMessage>("topic", 42, rclcpp::PublisherOptions());
|
||||
(void)publisher;
|
||||
}
|
||||
{
|
||||
auto publisher =
|
||||
rclcpp::create_publisher<IntraProcessMessage>(node, "topic", 42, rclcpp::PublisherOptions());
|
||||
(void)publisher;
|
||||
}
|
||||
// Now deprecated functions.
|
||||
#if !defined(_WIN32)
|
||||
# pragma GCC diagnostic push
|
||||
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
|
||||
#else // !defined(_WIN32)
|
||||
# pragma warning(push)
|
||||
# pragma warning(disable: 4996)
|
||||
#endif
|
||||
{
|
||||
auto publisher = node->create_publisher<IntraProcessMessage>("topic");
|
||||
(void)publisher;
|
||||
}
|
||||
{
|
||||
auto publisher = node->create_publisher<IntraProcessMessage>(
|
||||
"topic",
|
||||
42,
|
||||
std::make_shared<std::allocator<IntraProcessMessage>>());
|
||||
(void)publisher;
|
||||
}
|
||||
{
|
||||
auto publisher = node->create_publisher<IntraProcessMessage>("topic", rmw_qos_profile_default);
|
||||
(void)publisher;
|
||||
}
|
||||
{
|
||||
auto publisher = node->create_publisher<IntraProcessMessage>(
|
||||
"topic",
|
||||
rmw_qos_profile_default,
|
||||
std::make_shared<std::allocator<IntraProcessMessage>>());
|
||||
(void)publisher;
|
||||
}
|
||||
#if !defined(_WIN32)
|
||||
# pragma GCC diagnostic pop
|
||||
#else // !defined(_WIN32)
|
||||
# pragma warning(pop)
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
Testing publisher with intraprocess enabled and invalid QoS
|
||||
*/
|
||||
|
@ -98,9 +170,21 @@ TEST_F(TestPublisher, intraprocess_with_invalid_qos) {
|
|||
rmw_qos_profile_t qos = invalid_qos_profile();
|
||||
using rcl_interfaces::msg::IntraProcessMessage;
|
||||
{
|
||||
#if !defined(_WIN32)
|
||||
# pragma GCC diagnostic push
|
||||
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
|
||||
#else // !defined(_WIN32)
|
||||
# pragma warning(push)
|
||||
# pragma warning(disable: 4996)
|
||||
#endif
|
||||
ASSERT_THROW(
|
||||
{auto publisher = node->create_publisher<IntraProcessMessage>("topic", qos);},
|
||||
rclcpp::exceptions::InvalidParametersException);
|
||||
#if !defined(_WIN32)
|
||||
# pragma GCC diagnostic pop
|
||||
#else // !defined(_WIN32)
|
||||
# pragma warning(pop)
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -110,20 +194,20 @@ TEST_F(TestPublisher, intraprocess_with_invalid_qos) {
|
|||
TEST_F(TestPublisherSub, construction_and_destruction) {
|
||||
using rcl_interfaces::msg::IntraProcessMessage;
|
||||
{
|
||||
auto publisher = subnode->create_publisher<IntraProcessMessage>("topic");
|
||||
auto publisher = subnode->create_publisher<IntraProcessMessage>("topic", 42);
|
||||
|
||||
EXPECT_STREQ(publisher->get_topic_name(), "/ns/sub_ns/topic");
|
||||
}
|
||||
|
||||
{
|
||||
auto publisher = subnode->create_publisher<IntraProcessMessage>("/topic");
|
||||
auto publisher = subnode->create_publisher<IntraProcessMessage>("/topic", 42);
|
||||
|
||||
EXPECT_STREQ(publisher->get_topic_name(), "/topic");
|
||||
}
|
||||
|
||||
{
|
||||
ASSERT_THROW({
|
||||
auto publisher = subnode->create_publisher<IntraProcessMessage>("invalid_topic?");
|
||||
auto publisher = subnode->create_publisher<IntraProcessMessage>("invalid_topic?", 42);
|
||||
}, rclcpp::exceptions::InvalidTopicNameError);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -74,12 +74,12 @@ TEST_P(TestPublisherSubscriptionCount, increasing_and_decreasing_counts)
|
|||
"my_node",
|
||||
"/ns",
|
||||
parameters.node_options[0]);
|
||||
auto publisher = node->create_publisher<IntraProcessMessage>("/topic");
|
||||
auto publisher = node->create_publisher<IntraProcessMessage>("/topic", 10);
|
||||
|
||||
EXPECT_EQ(publisher->get_subscription_count(), 0u);
|
||||
EXPECT_EQ(publisher->get_intra_process_subscription_count(), 0u);
|
||||
{
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("/topic", &OnMessage);
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("/topic", 10, &OnMessage);
|
||||
rclcpp::sleep_for(offset);
|
||||
EXPECT_EQ(publisher->get_subscription_count(), 1u);
|
||||
EXPECT_EQ(
|
||||
|
@ -91,7 +91,7 @@ TEST_P(TestPublisherSubscriptionCount, increasing_and_decreasing_counts)
|
|||
"/ns",
|
||||
parameters.node_options[1]);
|
||||
auto another_sub =
|
||||
another_node->create_subscription<IntraProcessMessage>("/topic", &OnMessage);
|
||||
another_node->create_subscription<IntraProcessMessage>("/topic", 10, &OnMessage);
|
||||
|
||||
rclcpp::sleep_for(offset);
|
||||
EXPECT_EQ(publisher->get_subscription_count(), 2u);
|
||||
|
|
|
@ -56,8 +56,8 @@ TEST(TestSerializedMessageAllocator, borrow_from_subscription) {
|
|||
|
||||
auto node = std::make_shared<rclcpp::Node>("test_serialized_message_allocator_node");
|
||||
std::shared_ptr<rclcpp::SubscriptionBase> sub =
|
||||
node->create_subscription<test_msgs::msg::Empty>("~/dummy_topic", [](
|
||||
std::shared_ptr<test_msgs::msg::Empty> test_msg) {(void) test_msg;});
|
||||
node->create_subscription<test_msgs::msg::Empty>("~/dummy_topic", 10,
|
||||
[](std::shared_ptr<test_msgs::msg::Empty> test_msg) {(void) test_msg;});
|
||||
|
||||
auto msg0 = sub->create_serialized_message();
|
||||
EXPECT_EQ(0u, msg0->buffer_capacity);
|
||||
|
|
|
@ -95,7 +95,7 @@ public:
|
|||
auto callback = std::bind(
|
||||
&SubscriptionClassNodeInheritance::OnMessage, this, std::placeholders::_1);
|
||||
using rcl_interfaces::msg::IntraProcessMessage;
|
||||
auto sub = this->create_subscription<IntraProcessMessage>("topic", callback);
|
||||
auto sub = this->create_subscription<IntraProcessMessage>("topic", 10, callback);
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -112,7 +112,7 @@ public:
|
|||
auto node = std::make_shared<rclcpp::Node>("test_subscription_member_callback", "/ns");
|
||||
auto callback = std::bind(&SubscriptionClass::OnMessage, this, std::placeholders::_1);
|
||||
using rcl_interfaces::msg::IntraProcessMessage;
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("topic", callback);
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("topic", 10, callback);
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -125,12 +125,12 @@ TEST_F(TestSubscription, construction_and_destruction) {
|
|||
(void)msg;
|
||||
};
|
||||
{
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("topic", callback);
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("topic", 10, callback);
|
||||
}
|
||||
|
||||
{
|
||||
ASSERT_THROW({
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("invalid_topic?", callback);
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("invalid_topic?", 10, callback);
|
||||
}, rclcpp::exceptions::InvalidTopicNameError);
|
||||
}
|
||||
}
|
||||
|
@ -144,17 +144,17 @@ TEST_F(TestSubscriptionSub, construction_and_destruction) {
|
|||
(void)msg;
|
||||
};
|
||||
{
|
||||
auto sub = subnode->create_subscription<IntraProcessMessage>("topic", callback);
|
||||
auto sub = subnode->create_subscription<IntraProcessMessage>("topic", 1, callback);
|
||||
EXPECT_STREQ(sub->get_topic_name(), "/ns/sub_ns/topic");
|
||||
}
|
||||
|
||||
{
|
||||
auto sub = subnode->create_subscription<IntraProcessMessage>("/topic", callback);
|
||||
auto sub = subnode->create_subscription<IntraProcessMessage>("/topic", 1, callback);
|
||||
EXPECT_STREQ(sub->get_topic_name(), "/topic");
|
||||
}
|
||||
|
||||
{
|
||||
auto sub = subnode->create_subscription<IntraProcessMessage>("~/topic", callback);
|
||||
auto sub = subnode->create_subscription<IntraProcessMessage>("~/topic", 1, callback);
|
||||
std::string expected_topic_name =
|
||||
std::string(node->get_namespace()) + "/" + node->get_name() + "/topic";
|
||||
EXPECT_STREQ(sub->get_topic_name(), expected_topic_name.c_str());
|
||||
|
@ -162,11 +162,81 @@ TEST_F(TestSubscriptionSub, construction_and_destruction) {
|
|||
|
||||
{
|
||||
ASSERT_THROW({
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("invalid_topic?", callback);
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("invalid_topic?", 1, callback);
|
||||
}, rclcpp::exceptions::InvalidTopicNameError);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
Testing subscription creation signatures.
|
||||
*/
|
||||
TEST_F(TestSubscription, various_creation_signatures) {
|
||||
using rcl_interfaces::msg::IntraProcessMessage;
|
||||
auto cb = [](rcl_interfaces::msg::IntraProcessMessage::SharedPtr) {};
|
||||
{
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("topic", 1, cb);
|
||||
(void)sub;
|
||||
}
|
||||
{
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("topic", rclcpp::QoS(1), cb);
|
||||
(void)sub;
|
||||
}
|
||||
{
|
||||
auto sub =
|
||||
node->create_subscription<IntraProcessMessage>("topic", rclcpp::QoS(rclcpp::KeepLast(1)), cb);
|
||||
(void)sub;
|
||||
}
|
||||
{
|
||||
auto sub =
|
||||
node->create_subscription<IntraProcessMessage>("topic", rclcpp::QoS(rclcpp::KeepAll()), cb);
|
||||
(void)sub;
|
||||
}
|
||||
{
|
||||
auto sub = node->create_subscription<IntraProcessMessage>(
|
||||
"topic", 42, cb, rclcpp::SubscriptionOptions());
|
||||
(void)sub;
|
||||
}
|
||||
{
|
||||
auto sub = rclcpp::create_subscription<IntraProcessMessage>(
|
||||
node, "topic", 42, cb, rclcpp::SubscriptionOptions());
|
||||
(void)sub;
|
||||
}
|
||||
// Now deprecated functions.
|
||||
#if !defined(_WIN32)
|
||||
# pragma GCC diagnostic push
|
||||
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
|
||||
#else // !defined(_WIN32)
|
||||
# pragma warning(push)
|
||||
# pragma warning(disable: 4996)
|
||||
#endif
|
||||
{
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("topic", cb, 42);
|
||||
(void)sub;
|
||||
}
|
||||
{
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("topic", cb);
|
||||
(void)sub;
|
||||
}
|
||||
{
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("topic", cb, rmw_qos_profile_default);
|
||||
(void)sub;
|
||||
}
|
||||
{
|
||||
auto sub =
|
||||
node->create_subscription<IntraProcessMessage>("topic", cb, rmw_qos_profile_default, nullptr);
|
||||
(void)sub;
|
||||
}
|
||||
{
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("topic", cb, 42, nullptr);
|
||||
(void)sub;
|
||||
}
|
||||
#if !defined(_WIN32)
|
||||
# pragma GCC diagnostic pop
|
||||
#else // !defined(_WIN32)
|
||||
# pragma warning(pop)
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
Testing subscriptions using std::bind.
|
||||
*/
|
||||
|
@ -187,6 +257,6 @@ TEST_F(TestSubscription, callback_bind) {
|
|||
// Regression test for https://github.com/ros2/rclcpp/issues/479 where the TEST_F GTest macro
|
||||
// was interfering with rclcpp's `function_traits`.
|
||||
auto callback = std::bind(&TestSubscription::OnMessage, this, std::placeholders::_1);
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("topic", callback);
|
||||
auto sub = node->create_subscription<IntraProcessMessage>("topic", 1, callback);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -65,11 +65,11 @@ TEST_P(TestSubscriptionPublisherCount, increasing_and_decreasing_counts)
|
|||
"my_node",
|
||||
"/ns",
|
||||
node_options);
|
||||
auto subscription = node->create_subscription<IntraProcessMessage>("/topic", &OnMessage);
|
||||
auto subscription = node->create_subscription<IntraProcessMessage>("/topic", 10, &OnMessage);
|
||||
|
||||
EXPECT_EQ(subscription->get_publisher_count(), 0u);
|
||||
{
|
||||
auto pub = node->create_publisher<IntraProcessMessage>("/topic");
|
||||
auto pub = node->create_publisher<IntraProcessMessage>("/topic", 10);
|
||||
rclcpp::sleep_for(offset);
|
||||
EXPECT_EQ(subscription->get_publisher_count(), 1u);
|
||||
{
|
||||
|
@ -78,7 +78,7 @@ TEST_P(TestSubscriptionPublisherCount, increasing_and_decreasing_counts)
|
|||
"/ns",
|
||||
node_options);
|
||||
auto another_pub =
|
||||
another_node->create_publisher<IntraProcessMessage>("/topic");
|
||||
another_node->create_publisher<IntraProcessMessage>("/topic", 10);
|
||||
|
||||
rclcpp::sleep_for(offset);
|
||||
EXPECT_EQ(subscription->get_publisher_count(), 2u);
|
||||
|
|
|
@ -129,8 +129,7 @@ void trigger_clock_changes(
|
|||
std::shared_ptr<rclcpp::Clock> clock,
|
||||
bool expect_time_update = true)
|
||||
{
|
||||
auto clock_pub = node->create_publisher<rosgraph_msgs::msg::Clock>("clock",
|
||||
rmw_qos_profile_default);
|
||||
auto clock_pub = node->create_publisher<rosgraph_msgs::msg::Clock>("clock", 10);
|
||||
|
||||
for (int i = 0; i < 5; ++i) {
|
||||
if (!rclcpp::ok()) {
|
||||
|
|
|
@ -20,6 +20,7 @@ include_directories(include)
|
|||
|
||||
set(${PROJECT_NAME}_SRCS
|
||||
src/client.cpp
|
||||
src/qos.cpp
|
||||
src/server.cpp
|
||||
src/server_goal_handle.cpp
|
||||
src/types.cpp
|
||||
|
|
34
rclcpp_action/include/rclcpp_action/qos.hpp
Normal file
34
rclcpp_action/include/rclcpp_action/qos.hpp
Normal file
|
@ -0,0 +1,34 @@
|
|||
// 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.
|
||||
|
||||
#ifndef RCLCPP_ACTION__QOS_HPP_
|
||||
#define RCLCPP_ACTION__QOS_HPP_
|
||||
|
||||
#include <rclcpp/qos.hpp>
|
||||
|
||||
#include "rclcpp_action/visibility_control.hpp"
|
||||
|
||||
namespace rclcpp_action
|
||||
{
|
||||
|
||||
class DefaultActionStatusQoS : public rclcpp::QoS
|
||||
{
|
||||
public:
|
||||
RCLCPP_ACTION_PUBLIC
|
||||
DefaultActionStatusQoS();
|
||||
};
|
||||
|
||||
} // namespace rclcpp_action
|
||||
|
||||
#endif // RCLCPP_ACTION__QOS_HPP_
|
28
rclcpp_action/src/qos.cpp
Normal file
28
rclcpp_action/src/qos.cpp
Normal file
|
@ -0,0 +1,28 @@
|
|||
// 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 <rclcpp_action/qos.hpp>
|
||||
|
||||
#include <rcl_action/default_qos.h>
|
||||
|
||||
namespace rclcpp_action
|
||||
{
|
||||
|
||||
DefaultActionStatusQoS::DefaultActionStatusQoS()
|
||||
: rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rcl_action_qos_profile_status_default))
|
||||
{
|
||||
this->get_rmw_qos_profile() = rcl_action_qos_profile_status_default;
|
||||
}
|
||||
|
||||
} // namespace rclcpp_action
|
|
@ -42,6 +42,7 @@
|
|||
#include "rclcpp_action/exceptions.hpp"
|
||||
#include "rclcpp_action/create_client.hpp"
|
||||
#include "rclcpp_action/client.hpp"
|
||||
#include "rclcpp_action/qos.hpp"
|
||||
#include "rclcpp_action/types.hpp"
|
||||
|
||||
using namespace std::chrono_literals;
|
||||
|
@ -196,7 +197,8 @@ protected:
|
|||
ret = rcl_action_get_feedback_topic_name(
|
||||
action_name, allocator, &feedback_topic_name);
|
||||
ASSERT_EQ(RCL_RET_OK, ret);
|
||||
feedback_publisher = server_node->create_publisher<ActionFeedbackMessage>(feedback_topic_name);
|
||||
feedback_publisher =
|
||||
server_node->create_publisher<ActionFeedbackMessage>(feedback_topic_name, 10);
|
||||
ASSERT_TRUE(feedback_publisher != nullptr);
|
||||
allocator.deallocate(feedback_topic_name, allocator.state);
|
||||
|
||||
|
@ -205,7 +207,7 @@ protected:
|
|||
action_name, allocator, &status_topic_name);
|
||||
ASSERT_EQ(RCL_RET_OK, ret);
|
||||
status_publisher = server_node->create_publisher<ActionStatusMessage>(
|
||||
status_topic_name, rcl_action_qos_profile_status_default);
|
||||
status_topic_name, rclcpp_action::DefaultActionStatusQoS());
|
||||
ASSERT_TRUE(status_publisher != nullptr);
|
||||
allocator.deallocate(status_topic_name, allocator.state);
|
||||
server_executor.add_node(server_node);
|
||||
|
|
|
@ -367,7 +367,8 @@ TEST_F(TestServer, publish_status_accepted)
|
|||
// Subscribe to status messages
|
||||
std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs;
|
||||
auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>(
|
||||
"fibonacci/_action/status", [&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
|
||||
"fibonacci/_action/status", 10,
|
||||
[&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
|
||||
{
|
||||
received_msgs.push_back(list);
|
||||
});
|
||||
|
@ -428,7 +429,8 @@ TEST_F(TestServer, publish_status_canceling)
|
|||
// Subscribe to status messages
|
||||
std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs;
|
||||
auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>(
|
||||
"fibonacci/_action/status", [&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
|
||||
"fibonacci/_action/status", 10,
|
||||
[&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
|
||||
{
|
||||
received_msgs.push_back(list);
|
||||
});
|
||||
|
@ -483,7 +485,8 @@ TEST_F(TestServer, publish_status_canceled)
|
|||
// Subscribe to status messages
|
||||
std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs;
|
||||
auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>(
|
||||
"fibonacci/_action/status", [&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
|
||||
"fibonacci/_action/status", 10,
|
||||
[&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
|
||||
{
|
||||
received_msgs.push_back(list);
|
||||
});
|
||||
|
@ -540,7 +543,8 @@ TEST_F(TestServer, publish_status_succeeded)
|
|||
// Subscribe to status messages
|
||||
std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs;
|
||||
auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>(
|
||||
"fibonacci/_action/status", [&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
|
||||
"fibonacci/_action/status", 10,
|
||||
[&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
|
||||
{
|
||||
received_msgs.push_back(list);
|
||||
});
|
||||
|
@ -595,7 +599,8 @@ TEST_F(TestServer, publish_status_aborted)
|
|||
// Subscribe to status messages
|
||||
std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs;
|
||||
auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>(
|
||||
"fibonacci/_action/status", [&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
|
||||
"fibonacci/_action/status", 10,
|
||||
[&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list)
|
||||
{
|
||||
received_msgs.push_back(list);
|
||||
});
|
||||
|
@ -651,7 +656,7 @@ TEST_F(TestServer, publish_feedback)
|
|||
using FeedbackT = Fibonacci::Impl::FeedbackMessage;
|
||||
std::vector<FeedbackT::SharedPtr> received_msgs;
|
||||
auto subscriber = node->create_subscription<FeedbackT>(
|
||||
"fibonacci/_action/feedback", [&received_msgs](FeedbackT::SharedPtr msg)
|
||||
"fibonacci/_action/feedback", 10, [&received_msgs](FeedbackT::SharedPtr msg)
|
||||
{
|
||||
received_msgs.push_back(msg);
|
||||
});
|
||||
|
|
|
@ -49,8 +49,11 @@
|
|||
#include "rclcpp/node_interfaces/node_waitables_interface.hpp"
|
||||
#include "rclcpp/parameter.hpp"
|
||||
#include "rclcpp/publisher.hpp"
|
||||
#include "rclcpp/publisher_options.hpp"
|
||||
#include "rclcpp/qos.hpp"
|
||||
#include "rclcpp/service.hpp"
|
||||
#include "rclcpp/subscription.hpp"
|
||||
#include "rclcpp/subscription_options.hpp"
|
||||
#include "rclcpp/time.hpp"
|
||||
#include "rclcpp/timer.hpp"
|
||||
|
||||
|
@ -63,6 +66,29 @@
|
|||
namespace rclcpp_lifecycle
|
||||
{
|
||||
|
||||
// include these here to work around an esoteric Windows error where the namespace
|
||||
// cannot be used in the function declaration below without getting an error like:
|
||||
// 'rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>':
|
||||
// no appropriate default constructor available
|
||||
template<typename AllocatorT>
|
||||
using PublisherOptionsWithAllocator = rclcpp::PublisherOptionsWithAllocator<AllocatorT>;
|
||||
template<typename AllocatorT>
|
||||
using SubscriptionOptionsWithAllocator = rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>;
|
||||
|
||||
template<typename AllocatorT>
|
||||
PublisherOptionsWithAllocator<AllocatorT>
|
||||
create_default_publisher_options()
|
||||
{
|
||||
return rclcpp::PublisherOptionsWithAllocator<AllocatorT>();
|
||||
}
|
||||
|
||||
template<typename AllocatorT>
|
||||
SubscriptionOptionsWithAllocator<AllocatorT>
|
||||
create_default_subscription_options()
|
||||
{
|
||||
return rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>();
|
||||
}
|
||||
|
||||
/// LifecycleNode for creating lifecycle components
|
||||
/**
|
||||
* has lifecycle nodeinterface for configuring this node.
|
||||
|
@ -128,6 +154,22 @@ public:
|
|||
const std::vector<rclcpp::callback_group::CallbackGroup::WeakPtr> &
|
||||
get_callback_groups() const;
|
||||
|
||||
/// Create and return a Publisher.
|
||||
/**
|
||||
* \param[in] topic_name The topic for this publisher to publish on.
|
||||
* \param[in] qos The Quality of Service settings for this publisher.
|
||||
* \param[in] options The publisher options for this publisher.
|
||||
* \return Shared pointer to the created lifecycle publisher.
|
||||
*/
|
||||
template<typename MessageT, typename AllocatorT = std::allocator<void>>
|
||||
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, AllocatorT>>
|
||||
create_publisher(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::QoS & qos,
|
||||
const PublisherOptionsWithAllocator<AllocatorT> & options =
|
||||
create_default_publisher_options<AllocatorT>()
|
||||
);
|
||||
|
||||
/// Create and return a Publisher.
|
||||
/**
|
||||
* \param[in] topic_name The topic for this publisher to publish on.
|
||||
|
@ -136,10 +178,13 @@ public:
|
|||
* \return Shared pointer to the created publisher.
|
||||
*/
|
||||
template<typename MessageT, typename Alloc = std::allocator<void>>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated("use create_publisher(const std::string &, const rclcpp::QoS &, ...) instead")]]
|
||||
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, Alloc>>
|
||||
create_publisher(
|
||||
const std::string & topic_name, size_t qos_history_depth,
|
||||
std::shared_ptr<Alloc> allocator = nullptr);
|
||||
const std::string & topic_name,
|
||||
size_t qos_history_depth,
|
||||
std::shared_ptr<Alloc> allocator);
|
||||
|
||||
/// Create and return a LifecyclePublisher.
|
||||
/**
|
||||
|
@ -149,12 +194,44 @@ public:
|
|||
* \return Shared pointer to the created publisher.
|
||||
*/
|
||||
template<typename MessageT, typename Alloc = std::allocator<void>>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated("use create_publisher(const std::string &, const rclcpp::QoS &, ...) instead")]]
|
||||
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, Alloc>>
|
||||
create_publisher(
|
||||
const std::string & topic_name,
|
||||
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
|
||||
std::shared_ptr<Alloc> allocator = nullptr);
|
||||
|
||||
/// Create and return a Subscription.
|
||||
/**
|
||||
* \param[in] topic_name The topic to subscribe on.
|
||||
* \param[in] callback The user-defined callback function.
|
||||
* \param[in] qos The quality of service for this subscription.
|
||||
* \param[in] options The subscription options for this subscription.
|
||||
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
|
||||
* \return Shared pointer to the created subscription.
|
||||
*/
|
||||
/* TODO(jacquelinekay):
|
||||
Windows build breaks when static member function passed as default
|
||||
argument to msg_mem_strat, nullptr is a workaround.
|
||||
*/
|
||||
template<
|
||||
typename MessageT,
|
||||
typename CallbackT,
|
||||
typename AllocatorT = std::allocator<void>,
|
||||
typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>>
|
||||
std::shared_ptr<SubscriptionT>
|
||||
create_subscription(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::QoS & qos,
|
||||
CallbackT && callback,
|
||||
const SubscriptionOptionsWithAllocator<AllocatorT> & options =
|
||||
create_default_subscription_options<AllocatorT>(),
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, AllocatorT
|
||||
>::SharedPtr
|
||||
msg_mem_strat = nullptr);
|
||||
|
||||
/// Create and return a Subscription.
|
||||
/**
|
||||
* \param[in] topic_name The topic to subscribe on.
|
||||
|
@ -174,6 +251,10 @@ public:
|
|||
typename CallbackT,
|
||||
typename Alloc = std::allocator<void>,
|
||||
typename SubscriptionT = rclcpp::Subscription<MessageT, Alloc>>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated(
|
||||
"use create_subscription(const std::string &, const rclcpp::QoS &, CallbackT, ...) instead"
|
||||
)]]
|
||||
std::shared_ptr<SubscriptionT>
|
||||
create_subscription(
|
||||
const std::string & topic_name,
|
||||
|
@ -206,14 +287,19 @@ public:
|
|||
typename CallbackT,
|
||||
typename Alloc = std::allocator<void>,
|
||||
typename SubscriptionT = rclcpp::Subscription<MessageT, Alloc>>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated(
|
||||
"use create_subscription(const std::string &, const rclcpp::QoS &, CallbackT, ...) instead"
|
||||
)]]
|
||||
std::shared_ptr<SubscriptionT>
|
||||
create_subscription(
|
||||
const std::string & topic_name,
|
||||
size_t qos_history_depth,
|
||||
CallbackT && callback,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group,
|
||||
bool ignore_local_publications = false,
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>::SharedPtr
|
||||
msg_mem_strat = nullptr,
|
||||
std::shared_ptr<Alloc> allocator = nullptr);
|
||||
|
||||
|
@ -457,6 +543,11 @@ public:
|
|||
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr
|
||||
get_node_waitables_interface();
|
||||
|
||||
/// Return the NodeOptions used when creating this node.
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
const rclcpp::NodeOptions &
|
||||
get_node_options() const;
|
||||
|
||||
//
|
||||
// LIFECYCLE COMPONENTS
|
||||
//
|
||||
|
@ -585,7 +676,7 @@ private:
|
|||
rclcpp::node_interfaces::NodeTimeSourceInterface::SharedPtr node_time_source_;
|
||||
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
|
||||
|
||||
bool use_intra_process_comms_;
|
||||
const rclcpp::NodeOptions node_options_;
|
||||
|
||||
class LifecycleNodeInterfaceImpl;
|
||||
std::unique_ptr<LifecycleNodeInterfaceImpl> impl_;
|
||||
|
|
|
@ -39,18 +39,34 @@
|
|||
namespace rclcpp_lifecycle
|
||||
{
|
||||
|
||||
template<typename MessageT, typename AllocatorT>
|
||||
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, AllocatorT>>
|
||||
LifecycleNode::create_publisher(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::QoS & qos,
|
||||
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options)
|
||||
{
|
||||
using PublisherT = rclcpp_lifecycle::LifecyclePublisher<MessageT, AllocatorT>;
|
||||
return rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
|
||||
*this,
|
||||
topic_name,
|
||||
qos,
|
||||
options);
|
||||
}
|
||||
|
||||
template<typename MessageT, typename Alloc>
|
||||
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, Alloc>>
|
||||
LifecycleNode::create_publisher(
|
||||
const std::string & topic_name, size_t qos_history_depth,
|
||||
const std::string & topic_name,
|
||||
size_t qos_history_depth,
|
||||
std::shared_ptr<Alloc> allocator)
|
||||
{
|
||||
if (!allocator) {
|
||||
allocator = std::make_shared<Alloc>();
|
||||
}
|
||||
rmw_qos_profile_t qos = rmw_qos_profile_default;
|
||||
qos.depth = qos_history_depth;
|
||||
return this->create_publisher<MessageT, Alloc>(topic_name, qos, allocator);
|
||||
rclcpp::PublisherOptionsWithAllocator<Alloc> options;
|
||||
options.allocator = allocator;
|
||||
return this->create_publisher<MessageT, Alloc>(
|
||||
topic_name,
|
||||
rclcpp::QoS(rclcpp::KeepLast(qos_history_depth)),
|
||||
options);
|
||||
}
|
||||
|
||||
template<typename MessageT, typename Alloc>
|
||||
|
@ -60,21 +76,48 @@ LifecycleNode::create_publisher(
|
|||
const rmw_qos_profile_t & qos_profile,
|
||||
std::shared_ptr<Alloc> allocator)
|
||||
{
|
||||
using PublisherT = rclcpp_lifecycle::LifecyclePublisher<MessageT, Alloc>;
|
||||
rclcpp::QoS qos(rclcpp::QoSInitialization::from_rmw(qos_profile));
|
||||
qos.get_rmw_qos_profile() = qos_profile;
|
||||
|
||||
// create regular publisher in rclcpp::Node
|
||||
return rclcpp::create_publisher<MessageT, Alloc, PublisherT>(
|
||||
this->node_topics_.get(),
|
||||
rclcpp::PublisherOptionsWithAllocator<Alloc> pub_options;
|
||||
pub_options.allocator = allocator;
|
||||
|
||||
return this->create_publisher<MessageT, Alloc>(
|
||||
topic_name,
|
||||
qos_profile,
|
||||
rclcpp::PublisherEventCallbacks(),
|
||||
nullptr,
|
||||
use_intra_process_comms_,
|
||||
allocator);
|
||||
qos,
|
||||
pub_options);
|
||||
}
|
||||
|
||||
// TODO(karsten1987): Create LifecycleSubscriber
|
||||
template<typename MessageT, typename CallbackT, typename Alloc, typename SubscriptionT>
|
||||
template<
|
||||
typename MessageT,
|
||||
typename CallbackT,
|
||||
typename AllocatorT,
|
||||
typename SubscriptionT>
|
||||
std::shared_ptr<SubscriptionT>
|
||||
LifecycleNode::create_subscription(
|
||||
const std::string & topic_name,
|
||||
const rclcpp::QoS & qos,
|
||||
CallbackT && callback,
|
||||
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options,
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, AllocatorT>::SharedPtr
|
||||
msg_mem_strat)
|
||||
{
|
||||
return rclcpp::create_subscription<MessageT>(
|
||||
*this,
|
||||
topic_name,
|
||||
qos,
|
||||
std::forward<CallbackT>(callback),
|
||||
options,
|
||||
msg_mem_strat);
|
||||
}
|
||||
|
||||
template<
|
||||
typename MessageT,
|
||||
typename CallbackT,
|
||||
typename Alloc,
|
||||
typename SubscriptionT>
|
||||
std::shared_ptr<SubscriptionT>
|
||||
LifecycleNode::create_subscription(
|
||||
const std::string & topic_name,
|
||||
|
@ -87,28 +130,16 @@ LifecycleNode::create_subscription(
|
|||
msg_mem_strat,
|
||||
std::shared_ptr<Alloc> allocator)
|
||||
{
|
||||
using CallbackMessageT = typename rclcpp::subscription_traits::has_message_type<CallbackT>::type;
|
||||
rclcpp::QoS qos(rclcpp::QoSInitialization::from_rmw(qos_profile));
|
||||
qos.get_rmw_qos_profile() = qos_profile;
|
||||
|
||||
if (!allocator) {
|
||||
allocator = std::make_shared<Alloc>();
|
||||
}
|
||||
rclcpp::SubscriptionOptionsWithAllocator<Alloc> sub_options;
|
||||
sub_options.callback_group = group;
|
||||
sub_options.ignore_local_publications = ignore_local_publications;
|
||||
sub_options.allocator = allocator;
|
||||
|
||||
if (!msg_mem_strat) {
|
||||
using rclcpp::message_memory_strategy::MessageMemoryStrategy;
|
||||
msg_mem_strat = MessageMemoryStrategy<CallbackMessageT, Alloc>::create_default();
|
||||
}
|
||||
|
||||
return rclcpp::create_subscription<MessageT, CallbackT, Alloc, CallbackMessageT, SubscriptionT>(
|
||||
this->node_topics_.get(),
|
||||
topic_name,
|
||||
std::forward<CallbackT>(callback),
|
||||
qos_profile,
|
||||
rclcpp::SubscriptionEventCallbacks(),
|
||||
group,
|
||||
ignore_local_publications,
|
||||
use_intra_process_comms_,
|
||||
msg_mem_strat,
|
||||
allocator);
|
||||
return this->create_subscription<MessageT, CallbackT, Alloc, SubscriptionT>(
|
||||
topic_name, std::forward<CallbackT>(callback), qos, sub_options, msg_mem_strat);
|
||||
}
|
||||
|
||||
template<
|
||||
|
@ -123,21 +154,22 @@ LifecycleNode::create_subscription(
|
|||
CallbackT && callback,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group,
|
||||
bool ignore_local_publications,
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr
|
||||
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
|
||||
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, Alloc>::SharedPtr
|
||||
msg_mem_strat,
|
||||
std::shared_ptr<Alloc> allocator)
|
||||
{
|
||||
rmw_qos_profile_t qos = rmw_qos_profile_default;
|
||||
qos.depth = qos_history_depth;
|
||||
return this->create_subscription<MessageT, CallbackT, Alloc>(
|
||||
rclcpp::SubscriptionOptionsWithAllocator<Alloc> sub_options;
|
||||
sub_options.callback_group = group;
|
||||
sub_options.ignore_local_publications = ignore_local_publications;
|
||||
sub_options.allocator = allocator;
|
||||
|
||||
return this->create_subscription<MessageT, CallbackT, Alloc, SubscriptionT>(
|
||||
topic_name,
|
||||
std::forward<CallbackT>(callback),
|
||||
qos,
|
||||
rclcpp::SubscriptionEventCallbacks(),
|
||||
group,
|
||||
ignore_local_publications,
|
||||
msg_mem_strat,
|
||||
allocator);
|
||||
rclcpp::QoS(rclcpp::KeepLast(qos_history_depth)),
|
||||
sub_options,
|
||||
msg_mem_strat);
|
||||
}
|
||||
|
||||
template<typename DurationRepT, typename DurationT, typename CallbackT>
|
||||
|
|
|
@ -68,7 +68,11 @@ LifecycleNode::LifecycleNode(
|
|||
const std::string & namespace_,
|
||||
const rclcpp::NodeOptions & options)
|
||||
: node_base_(new rclcpp::node_interfaces::NodeBase(
|
||||
node_name, namespace_, options)),
|
||||
node_name,
|
||||
namespace_,
|
||||
options.context(),
|
||||
*(options.get_rcl_node_options()),
|
||||
options.use_intra_process_comms())),
|
||||
node_graph_(new rclcpp::node_interfaces::NodeGraph(node_base_.get())),
|
||||
node_logging_(new rclcpp::node_interfaces::NodeLogging(node_base_.get())),
|
||||
node_timers_(new rclcpp::node_interfaces::NodeTimers(node_base_.get())),
|
||||
|
@ -88,10 +92,10 @@ LifecycleNode::LifecycleNode(
|
|||
node_services_,
|
||||
node_clock_,
|
||||
options.initial_parameters(),
|
||||
options.use_intra_process_comms(),
|
||||
options.start_parameter_services(),
|
||||
options.start_parameter_event_publisher(),
|
||||
options.parameter_event_qos_profile(),
|
||||
options.parameter_event_qos(),
|
||||
options.parameter_event_publisher_options(),
|
||||
options.allow_undeclared_parameters(),
|
||||
options.automatically_declare_initial_parameters()
|
||||
)),
|
||||
|
@ -105,7 +109,7 @@ LifecycleNode::LifecycleNode(
|
|||
node_parameters_
|
||||
)),
|
||||
node_waitables_(new rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
|
||||
use_intra_process_comms_(options.use_intra_process_comms()),
|
||||
node_options_(options),
|
||||
impl_(new LifecycleNodeInterfaceImpl(node_base_, node_services_))
|
||||
{
|
||||
impl_->init();
|
||||
|
@ -333,6 +337,11 @@ LifecycleNode::get_node_waitables_interface()
|
|||
return node_waitables_;
|
||||
}
|
||||
|
||||
const rclcpp::NodeOptions &
|
||||
LifecycleNode::get_node_options() const
|
||||
{
|
||||
return node_options_;
|
||||
}
|
||||
|
||||
////
|
||||
bool
|
||||
|
|
|
@ -217,7 +217,8 @@ TEST_F(TestDefaultStateMachine, lifecycle_subscriber) {
|
|||
auto test_node = std::make_shared<MoodyLifecycleNode<GoodMood>>("testnode");
|
||||
|
||||
auto cb = [](const std::shared_ptr<lifecycle_msgs::msg::State> msg) {(void) msg;};
|
||||
auto lifecycle_sub = test_node->create_subscription<lifecycle_msgs::msg::State>("~/empty", cb);
|
||||
auto lifecycle_sub =
|
||||
test_node->create_subscription<lifecycle_msgs::msg::State>("~/empty", 10, cb);
|
||||
|
||||
SUCCEED();
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue