remove features and related code which were deprecated in dashing (#852)
Signed-off-by: William Woodall <william@osrfoundation.org>
This commit is contained in:
parent
dfb144d3cb
commit
89119c6422
19 changed files with 3 additions and 1051 deletions
|
@ -170,38 +170,6 @@ public:
|
|||
create_default_publisher_options<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 allocator to use during publishing activities.
|
||||
* \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);
|
||||
|
||||
/// Create and return a LifecyclePublisher.
|
||||
/**
|
||||
* \param[in] topic_name The topic for this publisher to publish on.
|
||||
* \param[in] qos_profile The QoS settings for this publisher.
|
||||
* \param[in] allocator allocator to use during publishing activities.
|
||||
* \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.
|
||||
|
@ -232,77 +200,6 @@ public:
|
|||
>::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.
|
||||
* \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<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,
|
||||
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 allocator to be used during handling of subscription callbacks.
|
||||
* \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<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,
|
||||
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 a timer.
|
||||
/**
|
||||
* \param[in] period Time interval between triggers of the callback.
|
||||
|
@ -420,30 +317,6 @@ public:
|
|||
rcl_interfaces::msg::SetParametersResult
|
||||
set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters);
|
||||
|
||||
/// Set one parameter, unless that parameter has already been set.
|
||||
/**
|
||||
* \sa rclcpp::Node::set_parameter_if_not_set
|
||||
*/
|
||||
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.
|
||||
/**
|
||||
* \sa rclcpp::Node::set_parameters_if_not_set
|
||||
*/
|
||||
template<typename MapValueT>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated("use declare_parameters() instead")]]
|
||||
void
|
||||
set_parameters_if_not_set(
|
||||
const std::string & name,
|
||||
const std::map<std::string, MapValueT> & values);
|
||||
|
||||
/// Return the parameter by the given name.
|
||||
/**
|
||||
* \sa rclcpp::Node::get_parameter
|
||||
|
@ -499,19 +372,6 @@ public:
|
|||
const std::string & prefix,
|
||||
std::map<std::string, MapValueT> & values) const;
|
||||
|
||||
/// Get the parameter value; if not set, set the "alternative value" and store it in the node.
|
||||
/**
|
||||
* \sa rclcpp::Node::get_parameter_or_set
|
||||
*/
|
||||
template<typename ParameterT>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[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.
|
||||
/**
|
||||
* \sa rclcpp::Node::describe_parameter
|
||||
|
@ -556,16 +416,6 @@ public:
|
|||
set_on_parameters_set_callback(
|
||||
rclcpp_lifecycle::LifecycleNode::OnParametersSetCallbackType callback);
|
||||
|
||||
/// Register the callback for parameter changes
|
||||
/**
|
||||
* \sa rclcpp::Node::register_param_change_callback
|
||||
*/
|
||||
template<typename CallbackT>
|
||||
// cppcheck-suppress syntaxError // bug in cppcheck 1.82 for [[deprecated]] on templated function
|
||||
[[deprecated("use set_on_parameters_set_callback() instead")]]
|
||||
void
|
||||
register_param_change_callback(CallbackT && callback);
|
||||
|
||||
RCLCPP_LIFECYCLE_PUBLIC
|
||||
std::vector<std::string>
|
||||
get_node_names() const;
|
||||
|
|
|
@ -54,40 +54,6 @@ LifecycleNode::create_publisher(
|
|||
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,
|
||||
std::shared_ptr<Alloc> 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>
|
||||
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<MessageT, Alloc>>
|
||||
LifecycleNode::create_publisher(
|
||||
const std::string & topic_name,
|
||||
const rmw_qos_profile_t & qos_profile,
|
||||
std::shared_ptr<Alloc> allocator)
|
||||
{
|
||||
rclcpp::QoS qos(rclcpp::QoSInitialization::from_rmw(qos_profile));
|
||||
qos.get_rmw_qos_profile() = qos_profile;
|
||||
|
||||
rclcpp::PublisherOptionsWithAllocator<Alloc> pub_options;
|
||||
pub_options.allocator = allocator;
|
||||
|
||||
return this->create_publisher<MessageT, Alloc>(
|
||||
topic_name,
|
||||
qos,
|
||||
pub_options);
|
||||
}
|
||||
|
||||
// TODO(karsten1987): Create LifecycleSubscriber
|
||||
template<
|
||||
typename MessageT,
|
||||
|
@ -113,65 +79,6 @@ LifecycleNode::create_subscription(
|
|||
msg_mem_strat);
|
||||
}
|
||||
|
||||
template<
|
||||
typename MessageT,
|
||||
typename CallbackT,
|
||||
typename Alloc,
|
||||
typename SubscriptionT>
|
||||
std::shared_ptr<SubscriptionT>
|
||||
LifecycleNode::create_subscription(
|
||||
const std::string & topic_name,
|
||||
CallbackT && callback,
|
||||
const rmw_qos_profile_t & qos_profile,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group,
|
||||
bool ignore_local_publications,
|
||||
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)
|
||||
{
|
||||
rclcpp::QoS qos(rclcpp::QoSInitialization::from_rmw(qos_profile));
|
||||
qos.get_rmw_qos_profile() = qos_profile;
|
||||
|
||||
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, sub_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,
|
||||
size_t qos_history_depth,
|
||||
CallbackT && callback,
|
||||
rclcpp::callback_group::CallbackGroup::SharedPtr group,
|
||||
bool ignore_local_publications,
|
||||
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)
|
||||
{
|
||||
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),
|
||||
rclcpp::QoS(rclcpp::KeepLast(qos_history_depth)),
|
||||
sub_options,
|
||||
msg_mem_strat);
|
||||
}
|
||||
|
||||
template<typename DurationRepT, typename DurationT, typename CallbackT>
|
||||
typename rclcpp::WallTimer<CallbackT>::SharedPtr
|
||||
LifecycleNode::create_wall_timer(
|
||||
|
@ -290,47 +197,6 @@ LifecycleNode::get_parameter(const std::string & name, ParameterT & parameter) c
|
|||
return result;
|
||||
}
|
||||
|
||||
template<typename CallbackT>
|
||||
void
|
||||
LifecycleNode::register_param_change_callback(CallbackT && callback)
|
||||
{
|
||||
this->node_parameters_->set_on_parameters_set_callback(std::forward<CallbackT>(callback));
|
||||
}
|
||||
|
||||
template<typename ParameterT>
|
||||
void
|
||||
LifecycleNode::set_parameter_if_not_set(
|
||||
const std::string & name,
|
||||
const ParameterT & value)
|
||||
{
|
||||
rclcpp::Parameter parameter;
|
||||
if (!this->get_parameter(name, parameter)) {
|
||||
this->set_parameters({rclcpp::Parameter(name, value), });
|
||||
}
|
||||
}
|
||||
|
||||
// this is a partially-specialized version of set_parameter_if_not_set above,
|
||||
// where our concrete type for ParameterT is std::map, but the to-be-determined
|
||||
// type is the value in the map.
|
||||
template<typename MapValueT>
|
||||
void
|
||||
LifecycleNode::set_parameters_if_not_set(
|
||||
const std::string & name,
|
||||
const std::map<std::string, MapValueT> & values)
|
||||
{
|
||||
std::vector<rclcpp::Parameter> params;
|
||||
|
||||
for (const auto & val : values) {
|
||||
std::string param_name = name + "." + val.first;
|
||||
rclcpp::Parameter parameter;
|
||||
if (!this->get_parameter(param_name, parameter)) {
|
||||
params.push_back(rclcpp::Parameter(param_name, val.second));
|
||||
}
|
||||
}
|
||||
|
||||
this->set_parameters(params);
|
||||
}
|
||||
|
||||
// this is a partially-specialized version of get_parameter above,
|
||||
// where our concrete type for ParameterT is std::map, but the to-be-determined
|
||||
// type is the value in the map.
|
||||
|
@ -365,19 +231,5 @@ LifecycleNode::get_parameter_or(
|
|||
return got_parameter;
|
||||
}
|
||||
|
||||
template<typename ParameterT>
|
||||
void
|
||||
LifecycleNode::get_parameter_or_set(
|
||||
const std::string & name,
|
||||
ParameterT & value,
|
||||
const ParameterT & alternative_value)
|
||||
{
|
||||
bool got_parameter = get_parameter(name, value);
|
||||
if (!got_parameter) {
|
||||
this->set_parameters({rclcpp::Parameter(name, alternative_value), });
|
||||
value = alternative_value;
|
||||
}
|
||||
}
|
||||
|
||||
} // namespace rclcpp_lifecycle
|
||||
#endif // RCLCPP_LIFECYCLE__LIFECYCLE_NODE_IMPL_HPP_
|
||||
|
|
|
@ -113,53 +113,6 @@ public:
|
|||
rclcpp::Publisher<MessageT, Alloc>::publish(msg);
|
||||
}
|
||||
|
||||
/// LifecyclePublisher publish function
|
||||
/**
|
||||
* The publish function checks whether the communication
|
||||
* was enabled or disabled and forwards the message
|
||||
* to the actual rclcpp Publisher base class
|
||||
*/
|
||||
// Skip deprecated attribute in windows, as it raise a warning in template specialization.
|
||||
#if !defined(_WIN32)
|
||||
// Avoid raising a deprecated warning in template specialization in linux.
|
||||
# pragma GCC diagnostic push
|
||||
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
|
||||
[[deprecated(
|
||||
"publishing an unique_ptr is prefered when using intra process communication."
|
||||
" If using a shared_ptr, use publish(*msg).")]]
|
||||
#endif
|
||||
virtual void
|
||||
publish(const std::shared_ptr<const MessageT> & msg)
|
||||
{
|
||||
if (!enabled_) {
|
||||
RCLCPP_WARN(
|
||||
logger_,
|
||||
"Trying to publish message on the topic '%s', but the publisher is not activated",
|
||||
this->get_topic_name());
|
||||
|
||||
return;
|
||||
}
|
||||
rclcpp::Publisher<MessageT, Alloc>::publish(*msg);
|
||||
}
|
||||
|
||||
// Skip deprecated attribute in windows, as it raise a warning in template specialization.
|
||||
#if !defined(_WIN32)
|
||||
[[deprecated(
|
||||
"Use publish(*msg). Check against nullptr before calling if necessary.")]]
|
||||
#endif
|
||||
virtual void
|
||||
publish(const MessageT * msg)
|
||||
{
|
||||
if (!msg) {
|
||||
throw std::runtime_error("msg argument is nullptr");
|
||||
}
|
||||
this->publish(*msg);
|
||||
}
|
||||
|
||||
#if !defined(_WIN32)
|
||||
# pragma GCC diagnostic pop
|
||||
#endif
|
||||
|
||||
virtual void
|
||||
on_activate()
|
||||
{
|
||||
|
|
|
@ -31,17 +31,7 @@
|
|||
#include "rclcpp/node_interfaces/node_clock.hpp"
|
||||
#include "rclcpp/node_interfaces/node_graph.hpp"
|
||||
#include "rclcpp/node_interfaces/node_logging.hpp"
|
||||
// When compiling this file, Windows produces a deprecation warning for the
|
||||
// deprecated function prototype of NodeParameters::register_param_change_callback().
|
||||
// Other compilers do not.
|
||||
#if defined(_WIN32)
|
||||
# pragma warning(push)
|
||||
# pragma warning(disable: 4996)
|
||||
#endif
|
||||
#include "rclcpp/node_interfaces/node_parameters.hpp"
|
||||
#if defined(_WIN32)
|
||||
# pragma warning(pop)
|
||||
#endif
|
||||
#include "rclcpp/node_interfaces/node_services.hpp"
|
||||
#include "rclcpp/node_interfaces/node_time_source.hpp"
|
||||
#include "rclcpp/node_interfaces/node_timers.hpp"
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue