Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
18 changes: 0 additions & 18 deletions tf2_ros/include/tf2_ros/buffer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,24 +95,6 @@ class Buffer : public BufferInterface, public AsyncBufferInterface, public tf2::
RequiredInterfaces node_interfaces = RequiredInterfaces(),
const rclcpp::QoS & qos = rclcpp::ServicesQoS());

/** \brief Constructor for a Buffer object
* \param clock A clock to use for time and sleeping
* \param cache_time How long to keep a history of transforms
* \param node If passed advertise the view_frames service that exposes debugging information from the buffer
* \param qos If passed change the quality of service of the frames_server_ service
*/
template<class NodeT = rclcpp::Node::SharedPtr, class AllocatorT = std::allocator<void>,
std::enable_if_t<rcpputils::is_pointer<NodeT>::value, bool> = true>
[[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of NoteT")]]
Buffer(
rclcpp::Clock::SharedPtr clock,
tf2::Duration cache_time = tf2::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME),
NodeT && node = NodeT(),
const rclcpp::QoS & qos = rclcpp::ServicesQoS())
: Buffer(clock, cache_time, *node, qos)
{
}

/** \brief Get the transform between two frames by frame ID.
* \param target_frame The frame to which data should be transformed
* \param source_frame The frame where the data originated
Expand Down
7 changes: 0 additions & 7 deletions tf2_ros/include/tf2_ros/create_timer_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,13 +63,6 @@ class CreateTimerROS : public CreateTimerInterface
RequiredInterfaces node_interfaces,
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr);

[[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of multiple interfaces")]]
TF2_ROS_PUBLIC
CreateTimerROS(
NodeBaseInterface::SharedPtr node_base,
NodeTimersInterface::SharedPtr node_timers,
rclcpp::CallbackGroup::SharedPtr callback_group = nullptr);

virtual ~CreateTimerROS() = default;

/**
Expand Down
96 changes: 0 additions & 96 deletions tf2_ros/include/tf2_ros/message_filter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -220,102 +220,6 @@ class MessageFilter : public MessageFilterBase, public message_filters::SimpleFi
connectInput(f);
}

/**
* \brief Constructor
*
* \param buffer The buffer this filter should use
* \param target_frame The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function.
* \param queue_size The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous).
* \param node The ros2 node to use for logging and clock operations
* \param buffer_timeout The timeout duration after requesting transforms from the buffer.
*/
template<typename TimeRepT = int64_t, typename TimeT = std::nano>
[[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of Node::SharedPtr&")]]
MessageFilter(
BufferT & buffer, const std::string & target_frame, uint32_t queue_size,
const rclcpp::Node::SharedPtr & node,
std::chrono::duration<TimeRepT, TimeT> buffer_timeout =
std::chrono::duration<TimeRepT, TimeT>::max())
: MessageFilter(
buffer, target_frame, queue_size,
RequiredInterfaces(node->get_node_logging_interface(), node->get_node_clock_interface()),
buffer_timeout)
{
}

/**
* \brief Constructor
*
* \param buffer The buffer this filter should use
* \param target_frame The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function.
* \param queue_size The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous).
* \param node_logging The logging interface to use for any log messages
* \param node_clock The clock interface to use to get the node clock
* \param buffer_timeout The timeout duration after requesting transforms from the buffer.
*/
template<typename TimeRepT = int64_t, typename TimeT = std::nano>
[[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of multiple interfaces")]]
MessageFilter(
BufferT & buffer, const std::string & target_frame, uint32_t queue_size,
const NodeLoggingInterface::SharedPtr & node_logging,
const NodeClockInterface::SharedPtr & node_clock,
std::chrono::duration<TimeRepT, TimeT> buffer_timeout =
std::chrono::duration<TimeRepT, TimeT>::max())
: MessageFilter(
buffer, target_frame, queue_size,
RequiredInterfaces(node_logging, node_clock), buffer_timeout)
{
}

/**
* \brief Constructor
*
* \param f The filter to connect this filter's input to. Often will be a message_filters::Subscriber.
* \param buffer The buffer this filter should use
* \param target_frame The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function.
* \param queue_size The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous).
* \param node The ros2 node to use for logging and clock operations
* \param buffer_timeout The timeout duration after requesting transforms from the buffer.
*/
template<class F, typename TimeRepT = int64_t, typename TimeT = std::nano>
[[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of Node::SharedPtr&")]]
MessageFilter(
F & f, BufferT & buffer, const std::string & target_frame, uint32_t queue_size,
const rclcpp::Node::SharedPtr & node,
std::chrono::duration<TimeRepT, TimeT> buffer_timeout =
std::chrono::duration<TimeRepT, TimeT>::max())
: MessageFilter(
f, buffer, target_frame, queue_size,
RequiredInterfaces(node->get_node_logging_interface(), node->get_node_clock_interface()),
buffer_timeout)
{
}

/**
* \brief Constructor
*
* \param f The filter to connect this filter's input to. Often will be a message_filters::Subscriber.
* \param buffer The buffer this filter should use
* \param target_frame The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function.
* \param queue_size The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous).
* \param node_logging The logging interface to use for any log messages
* \param node_clock The clock interface to use to get the node clock
* \param buffer_timeout The timeout duration after requesting transforms from the buffer.
*/
template<class F, typename TimeRepT = int64_t, typename TimeT = std::nano>
[[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of multiple interfaces")]]
MessageFilter(
F & f, BufferT & buffer, const std::string & target_frame, uint32_t queue_size,
const NodeLoggingInterface::SharedPtr & node_logging,
const NodeClockInterface::SharedPtr & node_clock,
std::chrono::duration<TimeRepT, TimeT> buffer_timeout =
std::chrono::duration<TimeRepT, TimeT>::max())
: MessageFilter(
f, buffer, target_frame, queue_size,
RequiredInterfaces(node_logging, node_clock), buffer_timeout)
{
}

/**
* \brief Connect this filter's input to another filter's output. If this filter is already connected, disconnects first.
*/
Expand Down
43 changes: 0 additions & 43 deletions tf2_ros/include/tf2_ros/static_transform_broadcaster.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,6 @@
#define TF2_ROS__STATIC_TRANSFORM_BROADCASTER_HPP_

#include <memory>
#include <type_traits>
#include <vector>

#include "tf2_ros/visibility_control.hpp"
Expand All @@ -45,7 +44,6 @@
#include "rclcpp/node_interfaces/get_node_parameters_interface.hpp"
#include "rclcpp/node_interfaces/get_node_topics_interface.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rcpputils/pointer_traits.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "tf2_msgs/msg/tf_message.hpp"
#include "tf2_ros/qos.hpp"
Expand Down Expand Up @@ -85,47 +83,6 @@ class StaticTransformBroadcaster
node_parameters, node_topics, "/tf_static", qos, options);
}

/** \brief Node constructor */
template<class NodeT, class AllocatorT = std::allocator<void>,
std::enable_if_t<rcpputils::is_pointer<NodeT>::value, bool> = true>
[[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of NodeT")]]
StaticTransformBroadcaster(
NodeT && node,
const rclcpp::QoS & qos = StaticBroadcasterQoS(),
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = [] () {
rclcpp::PublisherOptionsWithAllocator<AllocatorT> options;
options.qos_overriding_options = rclcpp::QosOverridingOptions{
rclcpp::QosPolicyKind::Depth,
rclcpp::QosPolicyKind::History,
rclcpp::QosPolicyKind::Reliability};
return options;
} ())
: StaticTransformBroadcaster(
RequiredInterfaces(node->get_node_parameters_interface(),
node->get_node_topics_interface()), qos, options)
{
}

/** \brief Node interfaces constructor */
template<class AllocatorT = std::allocator<void>>
[[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of multiple interfaces")]]
StaticTransformBroadcaster(
NodeParametersInterface::SharedPtr node_parameters,
NodeTopicsInterface::SharedPtr node_topics,
const rclcpp::QoS & qos = StaticBroadcasterQoS(),
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = [] () {
rclcpp::PublisherOptionsWithAllocator<AllocatorT> options;
options.qos_overriding_options = rclcpp::QosOverridingOptions{
rclcpp::QosPolicyKind::Depth,
rclcpp::QosPolicyKind::History,
rclcpp::QosPolicyKind::Reliability};
return options;
} ())
: StaticTransformBroadcaster(
RequiredInterfaces(node_parameters, node_topics), qos, options)
{
}

/** \brief Send a TransformStamped message
* The stamped data structure includes frame_id, and time, and parent_id already. */
TF2_ROS_PUBLIC
Expand Down
44 changes: 0 additions & 44 deletions tf2_ros/include/tf2_ros/transform_broadcaster.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,6 @@
#define TF2_ROS__TRANSFORM_BROADCASTER_HPP_

#include <memory>
#include <type_traits>
#include <vector>

#include "tf2_ros/visibility_control.hpp"
Expand All @@ -45,7 +44,6 @@
#include "rclcpp/node_interfaces/get_node_parameters_interface.hpp"
#include "rclcpp/node_interfaces/get_node_topics_interface.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rcpputils/pointer_traits.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "tf2_msgs/msg/tf_message.hpp"
#include "tf2_ros/qos.hpp"
Expand Down Expand Up @@ -87,48 +85,6 @@ class TransformBroadcaster
node_parameters, node_topics, "/tf", qos, options);
}

/** \brief Node constructor */
template<class NodeT, class AllocatorT = std::allocator<void>,
std::enable_if_t<rcpputils::is_pointer<NodeT>::value, bool> = true>
[[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of NodeT")]]
TransformBroadcaster(
NodeT && node,
const rclcpp::QoS & qos = DynamicBroadcasterQoS(),
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = [] () {
rclcpp::PublisherOptionsWithAllocator<AllocatorT> options;
options.qos_overriding_options = rclcpp::QosOverridingOptions{
rclcpp::QosPolicyKind::Depth,
rclcpp::QosPolicyKind::Durability,
rclcpp::QosPolicyKind::History,
rclcpp::QosPolicyKind::Reliability};
return options;
} ())
: TransformBroadcaster(
RequiredInterfaces(node->get_node_parameters_interface(),
node->get_node_topics_interface()), qos, options)
{
}

/** \brief Node interfaces constructor */
template<class AllocatorT = std::allocator<void>>
[[deprecated("Use rclcpp::node_interfaces::NodeInterfaces instead of multiple interfaces")]]
TransformBroadcaster(
NodeParametersInterface::SharedPtr node_parameters,
NodeTopicsInterface::SharedPtr node_topics,
const rclcpp::QoS & qos = DynamicBroadcasterQoS(),
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = [] () {
rclcpp::PublisherOptionsWithAllocator<AllocatorT> options;
options.qos_overriding_options = rclcpp::QosOverridingOptions{
rclcpp::QosPolicyKind::Depth,
rclcpp::QosPolicyKind::Durability,
rclcpp::QosPolicyKind::History,
rclcpp::QosPolicyKind::Reliability};
return options;
} ())
: TransformBroadcaster(RequiredInterfaces(node_parameters, node_topics), qos, options)
{
}

/** \brief Send a TransformStamped message
*
* The transform ʰTₐ added is from `child_frame_id`, `a` to `header.frame_id`,
Expand Down
Loading