AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
RosSubscriberNode< MessageT > Class Template Reference

Generic behavior tree node wrapper for a ROS 2 subscriber. More...

#include <auto_apms_behavior_tree_core/node/ros_subscriber_node.hpp>

Public Member Functions

 RosSubscriberNode (const std::string &instance_name, const Config &config, Context context, const rclcpp::QoS &qos={10})
 Constructor.
 
virtual BT::NodeStatus onTick (const std::shared_ptr< MessageT > &last_msg_ptr)
 Callback invoked when the node is ticked.
 
virtual BT::NodeStatus onMessageReceived (const MessageT &msg)
 Callback invoked when the node is ticked and a valid message has been received.
 
bool createSubscriber (const std::string &topic_name)
 Create the ROS 2 subscriber.
 
std::string getTopicName () const
 Get the name of the topic name this node subscribes to.
 

Static Public Member Functions

static BT::PortsList providedBasicPorts (BT::PortsList addition)
 Derived nodes implementing the static method RosSubscriberNode::providedPorts may call this method to also include the default port for ROS 2 behavior tree nodes.
 
static BT::PortsList providedPorts ()
 If a behavior tree requires input/output data ports, the developer must define this method accordingly.
 

Detailed Description

template<class MessageT>
class auto_apms_behavior_tree::core::RosSubscriberNode< MessageT >

Generic behavior tree node wrapper for a ROS 2 subscriber.

When ticked, this node may inspect the last message that has been received on a specific topic. Inheriting classes must reimplement the virtual methods as described below.

By default, the name of the topic will be determined as follows:

  1. If a value is passed using the input port named port, use that.
  2. Otherwise, use the value from NodeRegistrationOptions::port passed on construction as part of RosNodeContext.

It is possible to customize which port is used to determine the topic name and also extend the input's value with a prefix or suffix. This is achieved by including the special pattern (input:<port_name>) in NodeRegistrationOptions::port and replacing <port_name> with the desired input port name.

Example: Given the user implements an input port BT::InputPort<std::string>("my_port"), one may create a client for the topic "foo/bar" by defining NodeRegistrationOptions::port as (input:my_port)/bar and providing the string "foo" to the port with name my_port.

Additionally, the following characteristics depend on NodeRegistrationOptions:

  • logger_level: Minimum severity level enabled for logging using the ROS 2 Logger API.
Template Parameters
MessageTType of the ROS 2 message.

Definition at line 59 of file ros_subscriber_node.hpp.

Constructor & Destructor Documentation

◆ RosSubscriberNode()

template<class MessageT>
RosSubscriberNode ( const std::string & instance_name,
const Config & config,
Context context,
const rclcpp::QoS & qos = {10} )
inlineexplicit

Constructor.

Derived nodes are automatically created by TreeBuilder::instantiate when included inside a node manifest associated with the behavior tree resource.

Parameters
instance_nameName given to this specific node instance.
configStructure of internal data determined at runtime by BT::BehaviorTreeFactory.
contextAdditional parameters specific to ROS 2 determined at runtime by TreeBuilder.
qosQuality of service settings forwarded to the subscriber.

Definition at line 196 of file ros_subscriber_node.hpp.

Member Function Documentation

◆ providedBasicPorts()

template<class MessageT>
static BT::PortsList providedBasicPorts ( BT::PortsList addition)
inlinestatic

Derived nodes implementing the static method RosSubscriberNode::providedPorts may call this method to also include the default port for ROS 2 behavior tree nodes.

Parameters
additionAdditional ports to add to the ports list.
Returns
List of ports containing the default port along with node-specific ports.

Definition at line 104 of file ros_subscriber_node.hpp.

◆ providedPorts()

template<class MessageT>
static BT::PortsList providedPorts ( )
inlinestatic

If a behavior tree requires input/output data ports, the developer must define this method accordingly.

Returns
List of ports used by this node.

Definition at line 115 of file ros_subscriber_node.hpp.

◆ onTick()

template<class MessageT>
BT::NodeStatus onTick ( const std::shared_ptr< MessageT > & last_msg_ptr)
inlinevirtual

Callback invoked when the node is ticked.

By default, this method forwards the most recent message to RosSubscriberNode::onMessageReceived and leaves it up to this method to determine the node's return status. If no message has been received yet, it immediately returns BT::NodeStatus::FAILURE. If you want to change that behavior, you should override this method.

Parameters
last_msg_ptrThe latest message received, since the last tick. Will be nullptr if no new message was received.
Returns
Return status of the node based on last_msg_ptr.

Definition at line 314 of file ros_subscriber_node.hpp.

◆ onMessageReceived()

template<class MessageT>
BT::NodeStatus onMessageReceived ( const MessageT & msg)
inlinevirtual

Callback invoked when the node is ticked and a valid message has been received.

This callback won't be invoked if no message is available at the time this node is ticked. If you need to evaluate an expression every time this node is ticked, refer to RosSubscriberNode::onTick instead and change its default implementation.

Parameters
msgMost recently received message.
Returns
Return status of the node based on msg.

Definition at line 321 of file ros_subscriber_node.hpp.

◆ createSubscriber()

template<class MessageT>
bool createSubscriber ( const std::string & topic_name)
inline

Create the ROS 2 subscriber.

Parameters
topic_nameName of the topic.
Returns
true if the subscriber was created successfully, false otherwise.

Definition at line 214 of file ros_subscriber_node.hpp.

◆ getTopicName()

template<class MessageT>
std::string getTopicName ( ) const
inline

Get the name of the topic name this node subscribes to.

Returns
String representing the topic name.

Definition at line 327 of file ros_subscriber_node.hpp.


The documentation for this class was generated from the following file: