Skip to content

Commit

Permalink
change API to encourage users to specify history depth always (#713)
Browse files Browse the repository at this point in the history
* 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>
  • Loading branch information
wjwwood authored May 8, 2019
1 parent 385cccc commit c769b1b
Show file tree
Hide file tree
Showing 53 changed files with 1,908 additions and 454 deletions.
40 changes: 31 additions & 9 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down
56 changes: 56 additions & 0 deletions rclcpp/cmake/rclcpp_add_build_failure_test.cmake
Original file line number Diff line number Diff line change
@@ -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()
6 changes: 4 additions & 2 deletions rclcpp/include/rclcpp/allocator/allocator_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand All @@ -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)
{
Expand Down
68 changes: 67 additions & 1 deletion rclcpp/include/rclcpp/create_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand All @@ -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_
74 changes: 74 additions & 0 deletions rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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,
Expand Down Expand Up @@ -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_
Loading

0 comments on commit c769b1b

Please sign in to comment.