Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
BT::Groot2Publisher Class Reference

The Groot2Publisher is used to create an interface between your BT.CPP executor and Groot2. More...

#include <groot2_publisher.h>

Inheritance diagram for BT::Groot2Publisher:
Inheritance graph
[legend]

Classes

struct  PImpl
 

Public Member Functions

 Groot2Publisher (const BT::Tree &tree, unsigned server_port=1667)
 
 Groot2Publisher (const Groot2Publisher &other)=delete
 
 Groot2Publisher (Groot2Publisher &&other)=default
 
std::chrono::milliseconds maxHeartbeatDelay () const
 
Groot2Publisheroperator= (const Groot2Publisher &other)=delete
 
Groot2Publisheroperator= (Groot2Publisher &&other)=default
 
void setMaxHeartbeatDelay (std::chrono::milliseconds delay)
 setMaxHeartbeatDelay is used to tell the publisher when a connection with Groot2 should be cancelled, if no heartbeat is received. More...
 
 ~Groot2Publisher () override
 
- Public Member Functions inherited from BT::StatusChangeLogger
bool enabled () const
 
void enableTransitionToIdle (bool enable)
 
StatusChangeLoggeroperator= (const StatusChangeLogger &other)=delete
 
StatusChangeLoggeroperator= (StatusChangeLogger &&other)=default
 
void setEnabled (bool enabled)
 
void setTimestampType (TimestampType type)
 
bool showsTransitionToIdle () const
 
 StatusChangeLogger (const StatusChangeLogger &other)=delete
 
 StatusChangeLogger (StatusChangeLogger &&other)=default
 
 StatusChangeLogger (TreeNode *root_node)
 
virtual ~StatusChangeLogger ()=default
 

Private Types

using Position = Monitor::Hook::Position
 

Private Member Functions

void callback (Duration timestamp, const TreeNode &node, NodeStatus prev_status, NodeStatus status) override
 
void enableAllHooks (bool enable)
 
void flush () override
 
std::vector< uint8_t > generateBlackboardsDump (const std::string &bb_list)
 
Monitor::Hook::Ptr getHook (Position pos, uint16_t node_uid)
 
void heartbeatLoop ()
 
bool insertHook (Monitor::Hook::Ptr breakpoint)
 
void removeAllHooks ()
 
bool removeHook (Position pos, uint16_t node_uid)
 
void serverLoop ()
 
bool unlockBreakpoint (Position pos, uint16_t node_uid, NodeStatus result, bool remove)
 
void updateStatusBuffer ()
 

Private Attributes

std::unique_ptr< PImpl_p
 

Static Private Attributes

static std::set< unsigned > used_ports
 
static std::mutex used_ports_mutex
 

Detailed Description

The Groot2Publisher is used to create an interface between your BT.CPP executor and Groot2.

An inter-process communication mechanism allows the two processes to communicate through a TCP port. The user should provide the port to be used in the constructor.

Definition at line 19 of file groot2_publisher.h.

Member Typedef Documentation

◆ Position

Definition at line 24 of file groot2_publisher.h.

Constructor & Destructor Documentation

◆ Groot2Publisher() [1/3]

BT::Groot2Publisher::Groot2Publisher ( const BT::Tree tree,
unsigned  server_port = 1667 
)

Definition at line 107 of file groot2_publisher.cpp.

◆ ~Groot2Publisher()

BT::Groot2Publisher::~Groot2Publisher ( )
override

Definition at line 175 of file groot2_publisher.cpp.

◆ Groot2Publisher() [2/3]

BT::Groot2Publisher::Groot2Publisher ( const Groot2Publisher other)
delete

◆ Groot2Publisher() [3/3]

BT::Groot2Publisher::Groot2Publisher ( Groot2Publisher &&  other)
default

Member Function Documentation

◆ callback()

void BT::Groot2Publisher::callback ( Duration  timestamp,
const TreeNode node,
NodeStatus  prev_status,
NodeStatus  status 
)
overrideprivatevirtual

Implements BT::StatusChangeLogger.

Definition at line 199 of file groot2_publisher.cpp.

◆ enableAllHooks()

void BT::Groot2Publisher::enableAllHooks ( bool  enable)
private

Definition at line 481 of file groot2_publisher.cpp.

◆ flush()

void BT::Groot2Publisher::flush ( )
overrideprivatevirtual

Implements BT::StatusChangeLogger.

Definition at line 227 of file groot2_publisher.cpp.

◆ generateBlackboardsDump()

std::vector< uint8_t > BT::Groot2Publisher::generateBlackboardsDump ( const std::string &  bb_list)
private

Definition at line 518 of file groot2_publisher.cpp.

◆ getHook()

Monitor::Hook::Ptr BT::Groot2Publisher::getHook ( Position  pos,
uint16_t  node_uid 
)
private

Definition at line 696 of file groot2_publisher.cpp.

◆ heartbeatLoop()

void BT::Groot2Publisher::heartbeatLoop ( )
private

Definition at line 497 of file groot2_publisher.cpp.

◆ insertHook()

bool BT::Groot2Publisher::insertHook ( Monitor::Hook::Ptr  breakpoint)
private

Definition at line 539 of file groot2_publisher.cpp.

◆ maxHeartbeatDelay()

std::chrono::milliseconds BT::Groot2Publisher::maxHeartbeatDelay ( ) const

Definition at line 170 of file groot2_publisher.cpp.

◆ operator=() [1/2]

Groot2Publisher& BT::Groot2Publisher::operator= ( const Groot2Publisher other)
delete

◆ operator=() [2/2]

Groot2Publisher& BT::Groot2Publisher::operator= ( Groot2Publisher &&  other)
default

◆ removeAllHooks()

void BT::Groot2Publisher::removeAllHooks ( )
private

Definition at line 670 of file groot2_publisher.cpp.

◆ removeHook()

bool BT::Groot2Publisher::removeHook ( Position  pos,
uint16_t  node_uid 
)
private

Definition at line 632 of file groot2_publisher.cpp.

◆ serverLoop()

void BT::Groot2Publisher::serverLoop ( )
private

Definition at line 232 of file groot2_publisher.cpp.

◆ setMaxHeartbeatDelay()

void BT::Groot2Publisher::setMaxHeartbeatDelay ( std::chrono::milliseconds  delay)

setMaxHeartbeatDelay is used to tell the publisher when a connection with Groot2 should be cancelled, if no heartbeat is received.

Default is 5000 ms

Definition at line 165 of file groot2_publisher.cpp.

◆ unlockBreakpoint()

bool BT::Groot2Publisher::unlockBreakpoint ( Position  pos,
uint16_t  node_uid,
NodeStatus  result,
bool  remove 
)
private

Definition at line 598 of file groot2_publisher.cpp.

◆ updateStatusBuffer()

void BT::Groot2Publisher::updateStatusBuffer ( )
private

Member Data Documentation

◆ _p

std::unique_ptr<PImpl> BT::Groot2Publisher::_p
private

Definition at line 72 of file groot2_publisher.h.

◆ used_ports

std::set< unsigned > BT::Groot2Publisher::used_ports
staticprivate

Definition at line 22 of file groot2_publisher.h.

◆ used_ports_mutex

std::mutex BT::Groot2Publisher::used_ports_mutex
staticprivate

Definition at line 21 of file groot2_publisher.h.


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


behaviortree_cpp_v4
Author(s): Davide Faconti
autogenerated on Fri Jun 28 2024 02:20:09