33 friend class RosActionNode;
35 friend class RosServiceNode;
37 friend class RosSubscriberNode;
39 friend class RosPublisherNode;
40 template <
class,
typename,
bool>
41 friend class NodeRegistrationTemplate;
53 rclcpp::Node::SharedPtr ros_node, rclcpp::CallbackGroup::SharedPtr tree_node_waitables_callback_group,
54 rclcpp::executors::SingleThreadedExecutor::SharedPtr tree_node_waitables_executor,
103 void modifyProvidedPortsListForRegistration(BT::PortsList & ports_list)
const;
105 BT::Expected<std::string> getTopicName(
const BT::TreeNode * node)
const;
107 BT::PortsRemapping copyAliasedPortValuesToOriginalPorts(
const BT::TreeNode * node)
const;
109 const std::string ros_node_name_;
110 const std::string fully_qualified_ros_node_name_;
111 rclcpp::Logger base_logger_;
114 rclcpp::Node::WeakPtr nh_;
116 rclcpp::CallbackGroup::WeakPtr cb_group_;
118 rclcpp::executors::SingleThreadedExecutor::WeakPtr executor_;
std::string getROSNodeName() const
Get the name of the ROS 2 node passed to the constructor.
rclcpp::Logger getChildLogger(const std::string &name)
Get a child logger created using the associated ROS 2 node.
rclcpp::Time getCurrentTime() const
Get the current time using the associated ROS 2 node.
RosNodeContext(rclcpp::Node::SharedPtr ros_node, rclcpp::CallbackGroup::SharedPtr tree_node_waitables_callback_group, rclcpp::executors::SingleThreadedExecutor::SharedPtr tree_node_waitables_executor, const NodeRegistrationOptions &options)
Constructor.
std::string getFullyQualifiedTreeNodeName(const BT::TreeNode *node, bool with_class_name=true) const
Create a string representing the detailed name of a behavior tree node.
std::string getFullyQualifiedRosNodeName() const
Get the fully qualified name of the ROS 2 node passed to the constructor.
YAML::Node getExtraOptions() const
Get the extra YAML options provided during node registration.
rclcpp::Logger getBaseLogger() const
Get the logger of the associated ROS 2 node.