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

#include <auto_apms_behavior_tree/node/ros_subscriber_node.hpp>

Inheritance diagram for RosSubscriberNode< MessageT >:

Public Types

using MessageType = MessageT
 
using Config = BT::NodeConfig
 
using Context = RosNodeContext
 

Public Member Functions

 RosSubscriberNode (const std::string &instance_name, const Config &config, const Context &context, const rclcpp::QoS &qos={ 10 })
 
virtual ~RosSubscriberNode ()
 
BT::NodeStatus tick () override final
 
virtual BT::NodeStatus onTick (const std::shared_ptr< MessageT > &last_msg_ptr)
 
virtual BT::NodeStatus onMessageReceived (const MessageT &msg)
 
std::string getFullName () const
 

Static Public Member Functions

static BT::PortsList providedBasicPorts (BT::PortsList addition)
 
static BT::PortsList providedPorts ()
 

Protected Member Functions

const ContextgetRosContext ()
 

Static Protected Member Functions

static std::mutex & registryMutex ()
 
static SubscribersRegistry & getRegistry ()
 

Protected Attributes

const rclcpp::Logger logger_
 

Detailed Description

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

Abstract class to wrap a Topic subscriber. Considering the example in the tutorial: https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Publisher-And-Subscriber.html.

The corresponding wrapper would be:

class SubscriberNode: RosSubscriberNode<std_msgs::msg::String>

The name of the topic will be determined as follows:

  1. If a value is passes in the BT::InputPort "topic_name", use that
  2. Otherwise, use the value in RosNodeContext::default_port_name

Definition at line 45 of file ros_subscriber_node.hpp.

Member Typedef Documentation

◆ MessageType

template<class MessageT >
using MessageType = MessageT

Definition at line 63 of file ros_subscriber_node.hpp.

◆ Config

template<class MessageT >
using Config = BT::NodeConfig

Definition at line 64 of file ros_subscriber_node.hpp.

◆ Context

template<class MessageT >
using Context = RosNodeContext

Definition at line 65 of file ros_subscriber_node.hpp.

Constructor & Destructor Documentation

◆ RosSubscriberNode()

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

Definition at line 172 of file ros_subscriber_node.hpp.

◆ ~RosSubscriberNode()

template<class MessageT >
virtual ~RosSubscriberNode ( )
inlinevirtual

Definition at line 70 of file ros_subscriber_node.hpp.

Member Function Documentation

◆ providedBasicPorts()

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

Any subclass of RosTopicNode that accepts parameters must provide a providedPorts method and call providedBasicPorts in it.

Parameters
additionAdditional ports to add to BT port list
Returns
BT::PortsList Containing basic ports along with node-specific ports

Definition at line 81 of file ros_subscriber_node.hpp.

◆ providedPorts()

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

Creates list of BT ports.

Returns
BT::PortsList Containing basic ports along with node-specific ports

Definition at line 92 of file ros_subscriber_node.hpp.

◆ tick()

template<class MessageT >
BT::NodeStatus tick ( )
inlinefinaloverride

Definition at line 252 of file ros_subscriber_node.hpp.

◆ onTick()

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

Callback invoked on every tick. You must return either SUCCESS or FAILURE.

By default, this function calls RosSubscriberNode::onMessageReceived if a new message was received, otherwise it immediately returns FAILURE.

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

Definition at line 288 of file ros_subscriber_node.hpp.

◆ onMessageReceived()

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

Callback invoked when a new message is received. You must return either SUCCESS or FAILURE.

This callback won't be invoked if no new message has been received since the last time it was called. If you need to evaluate an expression every time this node is ticked, refer to RosSubscriberNode::onTick instead.

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

Definition at line 296 of file ros_subscriber_node.hpp.

◆ getFullName()

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

Definition at line 302 of file ros_subscriber_node.hpp.

◆ getRosContext()

template<class MessageT >
const RosSubscriberNode< MessageT >::Context & getRosContext ( )
inlineprotected

Definition at line 314 of file ros_subscriber_node.hpp.

◆ registryMutex()

template<class MessageT >
std::mutex & registryMutex ( )
inlinestaticprotected

Definition at line 320 of file ros_subscriber_node.hpp.

◆ getRegistry()

template<class MessageT >
RosSubscriberNode< MessageT >::SubscribersRegistry & getRegistry ( )
inlinestaticprotected

Definition at line 327 of file ros_subscriber_node.hpp.

Member Data Documentation

◆ logger_

template<class MessageT >
const rclcpp::Logger logger_
protected

Definition at line 132 of file ros_subscriber_node.hpp.


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