Skip to content

Commit

Permalink
Use multiple inheritance in NodeInterfaceHandle
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <methylDragon@gmail.com>
  • Loading branch information
methylDragon committed Nov 10, 2022
1 parent 18497f0 commit b1796db
Show file tree
Hide file tree
Showing 6 changed files with 455 additions and 250 deletions.
51 changes: 38 additions & 13 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -1451,23 +1451,48 @@ class Node : public std::enable_shared_from_this<Node>

/// Return a NodeInterfaceHandle bound with the Node's internal node interfaces.
/**
* Specify which interfaces you want to bind using the temlplate parameters. Any unbound
* interfaces will be nullptr.
*
* For example:
* - ```node->get_node_handle<>()``` will bind no interfaces.
* - ```node->get_node_handle<rclcpp::node_interfaces::NodeBaseInterface>()```
* Specify which interfaces you want to bind using the template parameters by specifying
* interface support classes to use. Any unmentioned interfaces will be unavailable to bind.
*
* This method will return a NodeInterfaceHandle with no bound interfaces. You must set them using
* ```NodeInterfaceHandle->set_<interface_name>_interface(InterfaceT::SharedPtr interface)```
*
* You may use any of the available support classes in
* node_interfaces/node_interface_handle_helpers.hpp:
* - Base: Supports NodeBaseInterface
* - Clock: Supports NodeClockInterface
* - Graph: Supports NodeGraphInterface
* - Logging: Supports NodeLoggingInterface
* - Parameters: Supports NodeParametersInterface
* - Services: Supports NodeServicesInterface
* - TimeSource: Supports NodeTimeSourceInterface
* - Timers: Supports NodeTimersInterface
* - Topics: Supports NodeTopicsInterface
* - Waitables: Supports NodeWaitablesInterface
*
* Or you can define your own interface support classes!
*
* Each of the support classes should define:
* - Default constructor
* - Templated constructor taking NodeT
* - get_node_<interface_name>_interface()
* - set_node_<interface_name>_interface()
*
* Usage example:
* - ```NodeInterfaceHandle<rclcpp::node_interfaces::Base>(node)```
* will bind just the NodeBaseInterface.
* - ```node->get_node_handle<
* rclcpp::node_interfaces::NodeBaseInterface,
* rclcpp::node_interfaces::NodeClockInterface
* >()``` will bind the base and clock interfaces.
*
* \return a NodeInterfaceHandle bound with the Node's internal node interfaces.
* - ```NodeInterfaceHandle<
* rclcpp::node_interfaces::Base, rclcpp::node_interfaces::Clock>(node)```
* will bind both the NodeBaseInterface and NodeClockInterface.
*
* \sa rclcpp::node_interfaces::NodeInterfaceHandle
* \param[in] node Node-like object to bind the interfaces of.
* \returns a NodeInterfaceHandle::SharedPtr supporting the stated interfaces, but bound with none
* of them
*/
template<typename ... InterfaceTs>
typename rclcpp::node_interfaces::NodeInterfaceHandle<InterfaceTs...>::SharedPtr
get_node_handle();
get_node_interface_handle();

/// Return the sub-namespace, if this is a sub-node, otherwise an empty string.
/**
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -396,7 +396,7 @@ Node::get_parameters(

template<typename ... InterfaceTs>
typename rclcpp::node_interfaces::NodeInterfaceHandle<InterfaceTs...>::SharedPtr
Node::get_node_handle()
Node::get_node_interface_handle()
{
return std::make_shared<rclcpp::node_interfaces::NodeInterfaceHandle<InterfaceTs...>>(this);
}
Expand Down
Loading

0 comments on commit b1796db

Please sign in to comment.