The Rokubimini Bus Manager class. More...
#include <BusManager.hpp>
Public Types | |
using | DiagnosticsUpdaterPtr = std::shared_ptr< diagnostic_updater::Updater > |
using | NodeHandlePtr = std::shared_ptr< ros::NodeHandle > |
![]() | |
typedef std::shared_ptr< ros::NodeHandle > | NodeHandlePtr |
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< Rokubimini > | getRokubimini (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... | |
![]() | |
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::NodeHandle & | getNodeHandle () 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_ |
![]() | |
NodeHandlePtr | nh_ |
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.
using rokubimini::RokubiminiBusManager::DiagnosticsUpdaterPtr = std::shared_ptr<diagnostic_updater::Updater> |
Definition at line 25 of file BusManager.hpp.
using rokubimini::RokubiminiBusManager::NodeHandlePtr = std::shared_ptr<ros::NodeHandle> |
Definition at line 26 of file BusManager.hpp.
|
delete |
Default constructor.
|
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.
|
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.
|
overridedefault |
Default Destructor.
Definition at line 61 of file BusManager.hpp.
|
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).
rokubimini | The Rokubimini instance. |
Definition at line 98 of file BusManager.cpp.
|
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.
|
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.
rokubiminiName | The name of the Rokubimini. |
Definition at line 220 of file BusManager.hpp.
|
inline |
Creates ROS Diagnostics for each attached rokubimini.
Definition at line 382 of file BusManager.hpp.
|
inline |
Creates ROS Publishers for each attached rokubimini.
Definition at line 354 of file BusManager.hpp.
|
inline |
Creates ROS Services for each attached rokubimini.
Definition at line 368 of file BusManager.hpp.
|
virtual |
Creates rokubiminis from the parameter server.
Definition at line 117 of file BusManager.cpp.
|
inline |
|
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.
name | The name of the Rokubimini to be found. |
Definition at line 321 of file BusManager.hpp.
|
inline |
Definition at line 343 of file BusManager.hpp.
|
inline |
Returns true if the rokubimini with name is found.
name | The name of the Rokubimini to be found. |
Definition at line 298 of file BusManager.hpp.
|
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.
|
virtual |
Loads the configuration of the bus (bus parameters and rokubiminis).
Definition at line 102 of file BusManager.cpp.
|
pure virtual |
Loads bus-specific parameters from parameter server. It's pure virtual since it's implementation-specific.
|
pure virtual |
Loads the time_step from the Parameter Server.
It's virtual since it's implementation-specific.
|
pure virtual |
Publish the ROS Diagnostics for the Bus Manager. It's virtual since it's implementation specific.
|
inline |
Publishes the ROS Diagnostics for each attached rokubimini.
Definition at line 416 of file BusManager.hpp.
|
inline |
Publishes the ROS messages for each attached rokubimini.
Definition at line 395 of file BusManager.hpp.
|
inlinevirtual |
Reads the bus.
This method reads the bus which has been created by the BusManager.
Definition at line 196 of file BusManager.hpp.
|
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.
|
inline |
Sets the nodeHandle of the device.
nh | The nodeHanlde of the device. |
Definition at line 281 of file BusManager.hpp.
|
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.
|
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.
|
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.
|
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.
|
inline |
Definition at line 447 of file BusManager.hpp.
|
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.
|
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.
|
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.
|
inline |
Starts up all Rokubimini devices before communication has been established by the Bus Manager.
Definition at line 429 of file BusManager.hpp.
|
virtual |
Updates with new values from/to the Rokubiminis.
This method updates the Manager with new values (Readings) from the Rokubimini devices.
event | The worker event. |
Definition at line 68 of file BusManager.cpp.
|
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.
|
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.
|
protected |
Boolean that specifies if the Manager is already running.
Definition at line 546 of file BusManager.hpp.
|
protected |
The name of the bus.
Definition at line 529 of file BusManager.hpp.
|
protected |
The internal NodeHandle variable.
Definition at line 536 of file BusManager.hpp.
|
protected |
Definition at line 521 of file BusManager.hpp.