Public Types | Public Member Functions | Protected Attributes | List of all members
rokubimini::RokubiminiBusManager Class Referenceabstract

The Rokubimini Bus Manager class. More...

#include <BusManager.hpp>

Inheritance diagram for rokubimini::RokubiminiBusManager:
Inheritance graph
[legend]

Public Types

using DiagnosticsUpdaterPtr = std::shared_ptr< diagnostic_updater::Updater >
 
using NodeHandlePtr = std::shared_ptr< ros::NodeHandle >
 
- Public Types inherited from bota_node::Node
typedef std::shared_ptr< ros::NodeHandleNodeHandlePtr
 

Public Member Functions

virtual bool addRokubiminiToBus (const std::shared_ptr< Rokubimini > &rokubimini) const
 Adds a Rokubimini to Bus. More...
 
void cleanup () override
 Cleans up the Bus Manager Node. More...
 
virtual bool createRokubimini (const std::string &rokubiminiName)=0
 Creates an implementation-specific Rokubimini instance. More...
 
void createRokubiminiRosDiagnostics () const
 Creates ROS Diagnostics for each attached rokubimini. More...
 
void createRokubiminiRosPublishers () const
 Creates ROS Publishers for each attached rokubimini. More...
 
void createRokubiminiRosServices () const
 Creates ROS Services for each attached rokubimini. More...
 
virtual bool createRokubiminisFromParamServer ()
 Creates rokubiminis from the parameter server. More...
 
std::string getName () const
 Gets the name of the bus. More...
 
std::shared_ptr< RokubiminigetRokubimini (const std::string &name) const
 Returns the Rokubimini instance with name name. More...
 
std::vector< std::shared_ptr< Rokubimini > > getRokubiminis () const
 
bool hasRokubimini (const std::string &name)
 Returns true if the rokubimini with name is found. More...
 
bool init () override
 Initializes the Bus Manager Node. More...
 
virtual bool load ()
 Loads the configuration of the bus (bus parameters and rokubiminis). More...
 
virtual bool loadBusParameters ()=0
 Loads bus-specific parameters from parameter server. It's pure virtual since it's implementation-specific. More...
 
virtual double loadTimeStep ()=0
 Loads the time_step from the Parameter Server. More...
 
virtual void publishBusManagerRosDiagnostics ()=0
 Publish the ROS Diagnostics for the Bus Manager. It's virtual since it's implementation specific. More...
 
void publishRokubiminiRosDiagnostics () const
 Publishes the ROS Diagnostics for each attached rokubimini. More...
 
void publishRosMessages () const
 Publishes the ROS messages for each attached rokubimini. More...
 
virtual void readBus ()
 Reads the bus. More...
 
 RokubiminiBusManager ()=delete
 Default constructor. More...
 
 RokubiminiBusManager (const NodeHandlePtr &nh)
 Constructor with initialization list for the NodeHandle. More...
 
 RokubiminiBusManager (const std::string &busName, NodeHandlePtr nh)
 Constructor with initialization list for the name and NodeHandle. More...
 
virtual void setConfigMode ()
 Sets the devices controlled from the BusManager to config mode. More...
 
void setNodeHandle (const NodeHandlePtr &nh)
 Sets the nodeHandle of the device. More...
 
virtual void setRunMode ()
 Sets the devices controlled from the BusManager to run mode. More...
 
virtual void shutdown ()
 Shuts down everything. More...
 
virtual void shutdownBus ()
 Shuts down the bus. More...
 
void shutdownWithCommunication () const
 Shuts down every Rokubimini device after communication has been closed. More...
 
void shutdownWithoutCommunication () const
 
virtual bool startup ()
 Starts the communication with all the Rokubimini devices. More...
 
virtual bool startupCommunication ()
 Starts the communication through the bus. More...
 
void startupWithCommunication () const
 Starts up all Rokubimini devices after communication has been established from the Bus Manager. More...
 
void startupWithoutCommunication () const
 Starts up all Rokubimini devices before communication has been established by the Bus Manager. More...
 
virtual bool update (const bota_worker::WorkerEvent &event)
 Updates with new values from/to the Rokubiminis. More...
 
void updateProcessReading () const
 Updates all Rokubimini instances with new measurements. More...
 
virtual void writeToBus ()
 Writes to the buses. More...
 
 ~RokubiminiBusManager () override=default
 Default Destructor. More...
 
- Public Member Functions inherited from bota_node::Node
bool addWorker (const bota_worker::WorkerOptions &options)
 
bool addWorker (const std::string &name, const double timestep, bool(T::*fp)(const bota_worker::WorkerEvent &), T *obj, const int priority=0)
 
void cancelWorker (const std::string &name, const bool wait=true)
 
ros::NodeHandlegetNodeHandle () const
 
bool hasWorker (const std::string &name)
 
 Node ()=delete
 
 Node (NodeHandlePtr nh)
 
virtual void preCleanup ()
 
void shutdown ()
 
void stopAllWorkers ()
 
void stopAllWorkers (bool wait)
 
virtual ~Node ()=default
 

Protected Attributes

std::atomic< bool > isRunning_ { false }
 Boolean that specifies if the Manager is already running. More...
 
std::string name_
 The name of the bus. More...
 
NodeHandlePtr nh_
 The internal NodeHandle variable. More...
 
std::vector< std::shared_ptr< Rokubimini > > rokubiminis_
 
- Protected Attributes inherited from bota_node::Node
NodeHandlePtr nh_
 

Detailed Description

The Rokubimini Bus Manager class.

Base class which provides an extendable API. It's useful for creating a bus manager with an existing communication protocol.

Definition at line 22 of file BusManager.hpp.

Member Typedef Documentation

◆ DiagnosticsUpdaterPtr

Definition at line 25 of file BusManager.hpp.

◆ NodeHandlePtr

Definition at line 26 of file BusManager.hpp.

Constructor & Destructor Documentation

◆ RokubiminiBusManager() [1/3]

rokubimini::RokubiminiBusManager::RokubiminiBusManager ( )
delete

Default constructor.

◆ RokubiminiBusManager() [2/3]

rokubimini::RokubiminiBusManager::RokubiminiBusManager ( const std::string &  busName,
NodeHandlePtr  nh 
)
inlineexplicit

Constructor with initialization list for the name and NodeHandle.

This method constructs a RokubiminiBusManager and clears the contents of the protected vector rokubiminis_.

Definition at line 44 of file BusManager.hpp.

◆ RokubiminiBusManager() [3/3]

rokubimini::RokubiminiBusManager::RokubiminiBusManager ( const NodeHandlePtr nh)
inlineexplicit

Constructor with initialization list for the NodeHandle.

This method constructs a RokubiminiBusManager and clears the contents of the protected vector rokubiminis_.

Definition at line 58 of file BusManager.hpp.

◆ ~RokubiminiBusManager()

rokubimini::RokubiminiBusManager::~RokubiminiBusManager ( )
overridedefault

Default Destructor.

Definition at line 61 of file BusManager.hpp.

Member Function Documentation

◆ addRokubiminiToBus()

bool rokubimini::RokubiminiBusManager::addRokubiminiToBus ( const std::shared_ptr< Rokubimini > &  rokubimini) const
virtual

Adds a Rokubimini to Bus.

This method is used for adding a Rokubimini (implementation-specific) to the Bus (implementation-specific). This method is bound to each implementation and the reason that it's here, is because of runtime polymorphism through inheritance. It should be pointed that the methods in the children of this class, add the implementation pointer to the Rokubimini implementation (e.g. RokubiminiSerialImplPtr to the RokubiminiSerial instance).

Parameters
rokubiminiThe Rokubimini instance.

Definition at line 98 of file BusManager.cpp.

◆ cleanup()

void rokubimini::RokubiminiBusManager::cleanup ( )
overridevirtual

Cleans up the Bus Manager Node.

Used for shutting down the Bus Manager.

Implements bota_node::Node.

Definition at line 80 of file BusManager.cpp.

◆ createRokubimini()

bool rokubimini::RokubiminiBusManager::createRokubimini ( const std::string &  rokubiminiName)
pure virtual

Creates an implementation-specific Rokubimini instance.

This function creates a Rokubimini instance based on a given name. It's virtual because it's implementation-specific.

Parameters
rokubiminiNameThe name of the Rokubimini.
Returns
True if the operation succeeded.

Definition at line 220 of file BusManager.hpp.

◆ createRokubiminiRosDiagnostics()

void rokubimini::RokubiminiBusManager::createRokubiminiRosDiagnostics ( ) const
inline

Creates ROS Diagnostics for each attached rokubimini.

Definition at line 382 of file BusManager.hpp.

◆ createRokubiminiRosPublishers()

void rokubimini::RokubiminiBusManager::createRokubiminiRosPublishers ( ) const
inline

Creates ROS Publishers for each attached rokubimini.

Definition at line 354 of file BusManager.hpp.

◆ createRokubiminiRosServices()

void rokubimini::RokubiminiBusManager::createRokubiminiRosServices ( ) const
inline

Creates ROS Services for each attached rokubimini.

Definition at line 368 of file BusManager.hpp.

◆ createRokubiminisFromParamServer()

bool rokubimini::RokubiminiBusManager::createRokubiminisFromParamServer ( )
virtual

Creates rokubiminis from the parameter server.

Definition at line 117 of file BusManager.cpp.

◆ getName()

std::string rokubimini::RokubiminiBusManager::getName ( ) const
inline

Gets the name of the bus.

Returns
The name value.

Definition at line 268 of file BusManager.hpp.

◆ getRokubimini()

std::shared_ptr< Rokubimini > rokubimini::RokubiminiBusManager::getRokubimini ( const std::string &  name) const
inline

Returns the Rokubimini instance with name name.

This method is used for getting a Rokubimini instance based on its name. If there isn't such a Rokubimini in the Manager's list, a nullptr is returned.

Parameters
nameThe name of the Rokubimini to be found.

Definition at line 321 of file BusManager.hpp.

◆ getRokubiminis()

std::vector<std::shared_ptr<Rokubimini> > rokubimini::RokubiminiBusManager::getRokubiminis ( ) const
inline

Definition at line 343 of file BusManager.hpp.

◆ hasRokubimini()

bool rokubimini::RokubiminiBusManager::hasRokubimini ( const std::string &  name)
inline

Returns true if the rokubimini with name is found.

Parameters
nameThe name of the Rokubimini to be found.
Returns
True if the rokubimini with name is found.

Definition at line 298 of file BusManager.hpp.

◆ init()

bool rokubimini::RokubiminiBusManager::init ( )
overridevirtual

Initializes the Bus Manager Node.

Implements the initialization phase of the Bus Manager.

Implements bota_node::Node.

Definition at line 103 of file BusManager.hpp.

◆ load()

bool rokubimini::RokubiminiBusManager::load ( )
virtual

Loads the configuration of the bus (bus parameters and rokubiminis).

Definition at line 102 of file BusManager.cpp.

◆ loadBusParameters()

bool rokubimini::RokubiminiBusManager::loadBusParameters ( )
pure virtual

Loads bus-specific parameters from parameter server. It's pure virtual since it's implementation-specific.

◆ loadTimeStep()

double rokubimini::RokubiminiBusManager::loadTimeStep ( )
pure virtual

Loads the time_step from the Parameter Server.

It's virtual since it's implementation-specific.

◆ publishBusManagerRosDiagnostics()

void rokubimini::RokubiminiBusManager::publishBusManagerRosDiagnostics ( )
pure virtual

Publish the ROS Diagnostics for the Bus Manager. It's virtual since it's implementation specific.

◆ publishRokubiminiRosDiagnostics()

void rokubimini::RokubiminiBusManager::publishRokubiminiRosDiagnostics ( ) const
inline

Publishes the ROS Diagnostics for each attached rokubimini.

Definition at line 416 of file BusManager.hpp.

◆ publishRosMessages()

void rokubimini::RokubiminiBusManager::publishRosMessages ( ) const
inline

Publishes the ROS messages for each attached rokubimini.

Definition at line 395 of file BusManager.hpp.

◆ readBus()

void rokubimini::RokubiminiBusManager::readBus ( )
inlinevirtual

Reads the bus.

This method reads the bus which has been created by the BusManager.

Definition at line 196 of file BusManager.hpp.

◆ setConfigMode()

void rokubimini::RokubiminiBusManager::setConfigMode ( )
inlinevirtual

Sets the devices controlled from the BusManager to config mode.

This method allows the BusManager to set the devices to configuration mode before the startup() method is called for every Rokubimini instance.

Definition at line 208 of file BusManager.hpp.

◆ setNodeHandle()

void rokubimini::RokubiminiBusManager::setNodeHandle ( const NodeHandlePtr nh)
inline

Sets the nodeHandle of the device.

Parameters
nhThe nodeHanlde of the device.

Definition at line 281 of file BusManager.hpp.

◆ setRunMode()

void rokubimini::RokubiminiBusManager::setRunMode ( )
inlinevirtual

Sets the devices controlled from the BusManager to run mode.

This method allows the BusManager to set the devices to run mode after the startup() method is called for every Rokubimini instance.

Definition at line 220 of file BusManager.hpp.

◆ shutdown()

void rokubimini::RokubiminiBusManager::shutdown ( )
virtual

Shuts down everything.

Shuts down all the Rokubimini devices. Also stops the updateWorker thread that is running in parallel.

Definition at line 85 of file BusManager.cpp.

◆ shutdownBus()

void rokubimini::RokubiminiBusManager::shutdownBus ( )
inlinevirtual

Shuts down the bus.

This method shuts down the bus which has been created by the BusManager.

Definition at line 173 of file BusManager.hpp.

◆ shutdownWithCommunication()

void rokubimini::RokubiminiBusManager::shutdownWithCommunication ( ) const
inline

Shuts down every Rokubimini device after communication has been closed.

Shuts down every Rokubimini device before communication has been closed.

This method shuts down every Rokubimini device after the BusManager has terminated communication with the device. It's virtual since it's implementation-specific.

This method shuts down every Rokubimini device before the BusManager has terminated communication with the device. It's virtual since it's implementation-specific.

Definition at line 465 of file BusManager.hpp.

◆ shutdownWithoutCommunication()

void rokubimini::RokubiminiBusManager::shutdownWithoutCommunication ( ) const
inline

Definition at line 447 of file BusManager.hpp.

◆ startup()

bool rokubimini::RokubiminiBusManager::startup ( )
virtual

Starts the communication with all the Rokubimini devices.

This method starts the communication with all the Rokubimini devices.

Definition at line 47 of file BusManager.cpp.

◆ startupCommunication()

bool rokubimini::RokubiminiBusManager::startupCommunication ( )
inlinevirtual

Starts the communication through the bus.

This method starts the communication with each attached Rokubimini through the bus.

Definition at line 100 of file BusManager.hpp.

◆ startupWithCommunication()

void rokubimini::RokubiminiBusManager::startupWithCommunication ( ) const
inline

Starts up all Rokubimini devices after communication has been established from the Bus Manager.

This method is virtual because it's implementation-specific.

Definition at line 481 of file BusManager.hpp.

◆ startupWithoutCommunication()

void rokubimini::RokubiminiBusManager::startupWithoutCommunication ( ) const
inline

Starts up all Rokubimini devices before communication has been established by the Bus Manager.

Definition at line 429 of file BusManager.hpp.

◆ update()

bool rokubimini::RokubiminiBusManager::update ( const bota_worker::WorkerEvent event)
virtual

Updates with new values from/to the Rokubiminis.

This method updates the Manager with new values (Readings) from the Rokubimini devices.

Parameters
eventThe worker event.

Definition at line 68 of file BusManager.cpp.

◆ updateProcessReading()

void rokubimini::RokubiminiBusManager::updateProcessReading ( ) const
inline

Updates all Rokubimini instances with new measurements.

This method updates the internal Reading variable of all Rokubiminis, by getting the new values from its implementation.

Definition at line 497 of file BusManager.hpp.

◆ writeToBus()

void rokubimini::RokubiminiBusManager::writeToBus ( )
inlinevirtual

Writes to the buses.

This method writes to the bus which has been created by the BusManager.

Definition at line 185 of file BusManager.hpp.

Member Data Documentation

◆ isRunning_

std::atomic< bool > rokubimini::RokubiminiBusManager::isRunning_ { false }
protected

Boolean that specifies if the Manager is already running.

Definition at line 546 of file BusManager.hpp.

◆ name_

std::string rokubimini::RokubiminiBusManager::name_
protected

The name of the bus.

Definition at line 529 of file BusManager.hpp.

◆ nh_

NodeHandlePtr rokubimini::RokubiminiBusManager::nh_
protected

The internal NodeHandle variable.

Definition at line 536 of file BusManager.hpp.

◆ rokubiminis_

std::vector<std::shared_ptr<Rokubimini> > rokubimini::RokubiminiBusManager::rokubiminis_
protected

Definition at line 521 of file BusManager.hpp.


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


rokubimini_bus_manager
Author(s):
autogenerated on Sat Apr 15 2023 02:53:54