AutoAPMS
Resilient Robot Mission Management
|
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. | |
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:
port
, use that.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:
MessageT | Type of the ROS 2 message. |
Definition at line 59 of file ros_subscriber_node.hpp.
|
inlineexplicit |
Constructor.
Derived nodes are automatically created by TreeBuilder::instantiate when included inside a node manifest associated with the behavior tree resource.
instance_name | Name given to this specific node instance. |
config | Structure of internal data determined at runtime by BT::BehaviorTreeFactory. |
context | Additional parameters specific to ROS 2 determined at runtime by TreeBuilder. |
qos | Quality of service settings forwarded to the subscriber. |
Definition at line 196 of file ros_subscriber_node.hpp.
|
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.
addition | Additional ports to add to the ports list. |
Definition at line 104 of file ros_subscriber_node.hpp.
|
inlinestatic |
If a behavior tree requires input/output data ports, the developer must define this method accordingly.
Definition at line 115 of file ros_subscriber_node.hpp.
|
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.
last_msg_ptr | The latest message received, since the last tick. Will be nullptr if no new message was received. |
last_msg_ptr
. Definition at line 314 of file ros_subscriber_node.hpp.
|
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.
msg | Most recently received message. |
msg
. Definition at line 321 of file ros_subscriber_node.hpp.
|
inline |
Create the ROS 2 subscriber.
topic_name | Name of the topic. |
true
if the subscriber was created successfully, false
otherwise. Definition at line 214 of file ros_subscriber_node.hpp.
|
inline |
Get the name of the topic name this node subscribes to.
Definition at line 327 of file ros_subscriber_node.hpp.