#include <auto_apms_behavior_tree/node/ros_subscriber_node.hpp>
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:
- If a value is passes in the BT::InputPort "topic_name", use that
- Otherwise, use the value in RosNodeContext::default_port_name
Definition at line 45 of file ros_subscriber_node.hpp.
◆ MessageType
template<class MessageT >
◆ Config
template<class MessageT >
◆ Context
template<class MessageT >
◆ RosSubscriberNode()
template<class MessageT >
◆ ~RosSubscriberNode()
template<class MessageT >
◆ 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
-
addition | Additional 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 >
◆ 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_ptr | The 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
-
msg | Most 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 |
◆ getRosContext()
template<class MessageT >
◆ registryMutex()
template<class MessageT >
std::mutex & registryMutex |
( |
| ) |
|
|
inlinestaticprotected |
◆ getRegistry()
template<class MessageT >
◆ logger_
template<class MessageT >
const rclcpp::Logger logger_ |
|
protected |
The documentation for this class was generated from the following file: