Skip to content

Commit

Permalink
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
remove features and related code which were deprecated in dashing
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <william@osrfoundation.org>
wjwwood committed Sep 14, 2019

Verified

This commit was created on GitHub.com and signed with GitHub’s verified signature.
1 parent dfb144d commit 9bb1d4c
Showing 19 changed files with 21 additions and 1,069 deletions.
11 changes: 0 additions & 11 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -462,17 +462,6 @@ if(BUILD_TESTING)
"rcl")
target_link_libraries(test_multi_threaded_executor ${PROJECT_NAME})
endif()

ament_add_gtest(test_local_parameters test/test_local_parameters.cpp)
if(TARGET test_local_parameters)
ament_target_dependencies(test_local_parameters
"rcl_interfaces"
"rmw"
"rosidl_generator_cpp"
"rosidl_typesupport_cpp"
)
target_link_libraries(test_local_parameters ${PROJECT_NAME})
endif()
endif()

ament_package()
30 changes: 0 additions & 30 deletions rclcpp/include/rclcpp/create_publisher.hpp
Original file line number Diff line number Diff line change
@@ -29,36 +29,6 @@
namespace rclcpp
{

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,
const std::string & topic_name,
const rmw_qos_profile_t & qos_profile,
const PublisherEventCallbacks & event_callbacks,
rclcpp::callback_group::CallbackGroup::SharedPtr group,
bool use_intra_process_comms,
std::shared_ptr<AllocatorT> allocator)
{
auto publisher_options = rcl_publisher_get_default_options();
publisher_options.qos = qos_profile;

auto pub = node_topics->create_publisher(
topic_name,
rclcpp::create_publisher_factory<MessageT, AllocatorT, PublisherT>(event_callbacks, allocator),
publisher_options,
use_intra_process_comms);

node_topics->add_publisher(pub, group);

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()
53 changes: 6 additions & 47 deletions rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
@@ -29,49 +29,6 @@
namespace rclcpp
{

template<
typename MessageT,
typename CallbackT,
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,
const std::string & topic_name,
CallbackT && callback,
const rmw_qos_profile_t & qos_profile,
const SubscriptionEventCallbacks & event_callbacks,
rclcpp::callback_group::CallbackGroup::SharedPtr group,
bool ignore_local_publications,
bool use_intra_process_comms,
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
CallbackMessageT, AllocatorT>::SharedPtr
msg_mem_strat,
typename std::shared_ptr<AllocatorT> allocator)
{
auto subscription_options = rcl_subscription_get_default_options();
subscription_options.qos = qos_profile;
subscription_options.ignore_local_publications = ignore_local_publications;

auto factory = rclcpp::create_subscription_factory
<MessageT, CallbackT, AllocatorT, CallbackMessageT, SubscriptionT>(
std::forward<CallbackT>(callback),
event_callbacks,
msg_mem_strat,
allocator);

auto sub = node_topics->create_subscription(
topic_name,
factory,
subscription_options,
use_intra_process_comms);
node_topics->add_subscription(sub, group);
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()
@@ -83,8 +40,10 @@ template<
typename CallbackT,
typename AllocatorT = std::allocator<void>,
typename CallbackMessageT =
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type,
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type,
typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>,
typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
CallbackMessageT, AllocatorT>,
typename NodeT>
typename std::shared_ptr<SubscriptionT>
create_subscription(
@@ -95,9 +54,9 @@ create_subscription(
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
),
typename rclcpp::message_memory_strategy::MessageMemoryStrategy<
CallbackMessageT, AllocatorT>::SharedPtr
msg_mem_strat = nullptr)
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
MessageMemoryStrategyT::create_default()
))
{
using rclcpp::node_interfaces::get_node_topics_interface;
auto node_topics = get_node_topics_interface(std::forward<NodeT>(node));
197 changes: 9 additions & 188 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
@@ -174,7 +174,7 @@ class Node : public std::enable_shared_from_this<Node>
template<
typename MessageT,
typename AllocatorT = std::allocator<void>,
typename PublisherT = ::rclcpp::Publisher<MessageT, AllocatorT>>
typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>>
std::shared_ptr<PublisherT>
create_publisher(
const std::string & topic_name,
@@ -183,44 +183,6 @@ class Node : public std::enable_shared_from_this<Node>
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 Custom allocator.
* \return Shared pointer to the created publisher.
*/
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 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<AllocatorT> allocator);

/// Create and return a Publisher.
/**
* \param[in] topic_name The topic for this publisher to publish on.
* \param[in] qos_profile The quality of service profile to pass on to the rmw implementation.
* \param[in] allocator Optional custom allocator.
* \return Shared pointer to the created publisher.
*/
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 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<AllocatorT> allocator = nullptr);

/// Create and return a Subscription.
/**
* \param[in] topic_name The topic to subscribe on.
@@ -230,101 +192,25 @@ class Node : public std::enable_shared_from_this<Node>
* \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<
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type, AllocatorT>>
typename CallbackMessageT =
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type,
typename SubscriptionT = rclcpp::Subscription<CallbackMessageT, AllocatorT>,
typename MessageMemoryStrategyT =
rclcpp::message_memory_strategy::MessageMemoryStrategy<CallbackMessageT, AllocatorT>>
std::shared_ptr<SubscriptionT>
create_subscription(
const std::string & topic_name,
const rclcpp::QoS & qos,
CallbackT && callback,
const SubscriptionOptionsWithAllocator<AllocatorT> & options =
SubscriptionOptionsWithAllocator<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.
* \param[in] callback The user-defined callback function.
* \param[in] qos_profile The quality of service profile to pass on to the rmw implementation.
* \param[in] group The callback group for this subscription. NULL for no callback group.
* \param[in] ignore_local_publications True to ignore local publications.
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
* \param[in] allocator Optional custom allocator.
* \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 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,
CallbackT && callback,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_default,
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);

/// Create and return a Subscription.
/**
* \param[in] topic_name The topic to subscribe on.
* \param[in] qos_history_depth The depth of the subscription's incoming message queue.
* \param[in] callback The user-defined callback function.
* \param[in] group The callback group for this subscription. NULL for no callback group.
* \param[in] ignore_local_publications True to ignore local publications.
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
* \param[in] allocator Optional custom allocator.
* \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 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,
CallbackT && callback,
size_t qos_history_depth,
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);
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
MessageMemoryStrategyT::create_default()
));

/// Create a timer.
/**
@@ -624,38 +510,6 @@ class Node : public std::enable_shared_from_this<Node>
rcl_interfaces::msg::SetParametersResult
set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters);

/// Set one parameter, unless that parameter has already been set.
/**
* Set the given parameter unless already set.
*
* Deprecated, instead use declare_parameter().
*
* \param[in] parameters The vector of parameters to be set.
* \return The result of each set action as a vector.
*/
template<typename ParameterT>
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
[[deprecated("use declare_parameter() instead")]]
void
set_parameter_if_not_set(const std::string & name, const ParameterT & value);

/// Set a map of parameters with the same prefix.
/**
* For each key in the map, a parameter with a name of "name.key" will be set
* to the value in the map.
*
* Deprecated, instead use declare_parameters().
*
* \param[in] name The prefix of the parameters to set.
* \param[in] values The parameters to set in the given prefix.
*/
template<typename ParameterT>
[[deprecated("use declare_parameters() instead")]]
void
set_parameters_if_not_set(
const std::string & name,
const std::map<std::string, ParameterT> & values);

/// Return the parameter by the given name.
/**
* If the parameter has not been declared, then this method may throw the
@@ -799,28 +653,6 @@ class Node : public std::enable_shared_from_this<Node>
const std::string & prefix,
std::map<std::string, ParameterT> & values) const;

/// Get the parameter value; if not set, set the "alternative value" and store it in the node.
/**
* If the parameter is set, then the "value" argument is assigned the value
* in the parameter.
* If the parameter is not set, then the "value" argument is assigned the "alternative_value",
* and the parameter is set to the "alternative_value" on the node.
*
* Deprecated, instead use declare_parameter()'s return value, or use
* has_parameter() to ensure it exists before getting it.
*
* \param[in] name The name of the parameter to get.
* \param[out] value The output where the value of the parameter should be assigned.
* \param[in] alternative_value Value to be used if the parameter was not set.
*/
template<typename ParameterT>
[[deprecated("use declare_parameter() and its return value instead")]]
void
get_parameter_or_set(
const std::string & name,
ParameterT & value,
const ParameterT & alternative_value);

/// Return the parameter descriptor for the given parameter name.
/**
* Like get_parameters(), this method may throw the
@@ -1006,17 +838,6 @@ class Node : public std::enable_shared_from_this<Node>
OnParametersSetCallbackType
set_on_parameters_set_callback(rclcpp::Node::OnParametersSetCallbackType callback);

/// Register the callback for parameter changes
/**
* \param[in] callback User defined callback function.
* It is expected to atomically set parameters.
* \note Repeated invocations of this function will overwrite previous callbacks.
*/
template<typename CallbackT>
[[deprecated("use set_on_parameters_set_callback() instead")]]
void
register_param_change_callback(CallbackT && callback);

/// Get the fully-qualified names of all available nodes.
/**
* The fully-qualified name includes the local namespace and name of the node.
Loading

0 comments on commit 9bb1d4c

Please sign in to comment.