geometry2
geometry2 copied to clipboard
Instead of templating on NodeT, use rclcpp::node_interfaces::NodeInterfaces instead
Feature request
Feature description
tf2_ros currently has an established pattern of templating on a NodeT
to support taking in arbitrary node-like types (e.g. Node
, LifecycleNode
, etc.)
For example: https://github.com/ros2/geometry2/blob/fbda7c013f921c28e3b71bfc5bdf86b37a9992e8/tf2_ros/include/tf2_ros/buffer.h#L79-L85
This pattern of templating on NodeT
, however, means that a lot of business logic needs to be moved into a template function in the header, resulting in the need to recompile any dependents of tf2_ros if any business logic changes.
Instead, as per this ROSCon 2023 lightning talk, it would be better to defer that templating logic to the rclcpp::node_interfaces::NodeInterfaces
(https://github.com/ros2/rclcpp/pull/2041) class instead so that the logic can be moved to a .cpp
source file to avoid this recompilation.
Additionally:
- It would serve as better documentation, since the interfaces that are needed will be visible directly in the header.
- Template instantiation of the
NodeInterfaces
class can be shared across different classes that use it instead of instantiating different versions of constructors of each class in the case ofNodeT
That is, instead of:
// Templated!!
template<typename NodeT = rclcpp::Node::SharedPtr>
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())
: BufferCore(cache_time), clock_(clock), timer_interface_(nullptr)
We do something like:
// NOT templated!
Buffer(
rclcpp::Clock::SharedPtr clock,
tf2::Duration cache_time,
NodeInterfaces<
NodeBaseInterface, NodeLoggingInterface, NodeServicesInterface
> interfaces,
...) : interfaces_(std::move(interfaces)), ...
This would rely on the NodeInterfaces
class to aggregate the node interfaces we need, and we can store/copy that interfaces object in the tf2_ros class instead (as it is copyable).
Implementation considerations
I see a couple of classes to apply the NodeInterfaces pattern to:
- Buffer
- TransformBroadcaster
- StaticTransformBroadcaster
- TransformListener
(And technically anything that takes in multiple node interfaces)
- A new, non-templated constructor that takes
rclcpp::node_interfaces::NodeInterfaces
should be implemented and used to house the logic in a source file- Note:
NodeInterfaces
can only take in a non-pointerNodeT
, so any downstream usages must dereference any node-pointers they have to pass to it.
- Note:
- Classes with this constructor should copy the
NodeInterfaces
object (which will compose all shared_ptrs to the interfaces it uses), instead of copying the individual interfaces one by one. - We will still need templated constructor overloads for some types (since they default construct NodeT sometimes) that call the non-templated constructor
- Once classes are moved to use
NodeInterfaces
, many template functions will no longer need to be templated, and should have their logic be moved to source files as much as possible.
I'm unsure how many tf2_ros dependents in ros2.repos will get affected, changes might ripple out a little bit, but I think the re-compilation tradeoff is worth it.