The Rokubimini Manager class. More...
#include <Manager.hpp>
Public Member Functions | |
void | createRokubiminiRosPublishers () const |
Creates ROS Publishers for each attached rokubimini. More... | |
void | createRokubiminiRosServices () const |
Creates ROS Services for each attached rokubimini. 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 | loadSetup () override |
Loads the Setup from the parameter server. More... | |
void | publishRosMessages () const |
Publishes the ROS messages for each attached rokubimini. More... | |
RokubiminiManager ()=delete | |
RokubiminiManager (const bool standalone, const bool installSignalHandler, const double timeStep=0.01, const NodeHandlePtr nh=nullptr) | |
Custom constructor. The default constructor is deleted. More... | |
void | setNodeHandle (const std::shared_ptr< ros::NodeHandle > &nh) const |
Sets the ROS NodeHandle to each rokubimini. More... | |
void | shutdown () override |
Shuts down everything. More... | |
bool | startup () override |
Starts the communication with all the Rokubimini devices. More... | |
bool | update () override |
Updates with new values from/to the Rokubiminis. More... | |
void | updateCommunicationManagerReadMessages () |
Instructs each BusManager to read the messages. More... | |
void | updateCommunicationManagerWriteMessages () |
Instructs each BusManager to write the messages. More... | |
void | updateProcessReadings () |
Gets the Readings from each Rokubimini device. More... | |
~RokubiminiManager () override=default | |
Public Member Functions inherited from rokubimini::BaseManager | |
BaseManager () | |
Default constructor. More... | |
virtual | ~BaseManager ()=default |
Protected Member Functions | |
bool | addRokubimini (const std::shared_ptr< Rokubimini > &rokubimini) |
Adds a Rokubimini instance to the list. More... | |
bool | createAndConfigureRokubimini (const std::shared_ptr< rokubimini::setup::Rokubimini > &rokubiminiSetup) |
Creates an implementation-specific Rokubimini instance (through the rokubimini_factory), loads the RokubiminiSetup to it and adds the new instance to the list. More... | |
bool | createRokubiminisFromSetup (const rokubimini::setup::SetupPtr &setup) |
Creates the Rokubimini instances from a Setup. More... | |
void | handleSignal (const int signum) |
Handles the signal received. Specifically requests shuts down if the signum is SIGSEGV. More... | |
bool | loadBusManagersSetup () |
Calls the loadSetup() of each Bus Manager. More... | |
void | requestShutdown () |
Sets a flag that represents that shutdown has been requested. More... | |
bool | rokubiminiExists (const std::string &name) const |
Decides if a specific Rokubimini instance exists in the list. More... | |
bool | updateWorkerCb (const bota_worker::WorkerEvent &event) |
Callback method which when triggered calls the update() method. More... | |
Protected Attributes | |
std::vector< std::unique_ptr< RokubiminiBusManager > > | busManagers_ |
std::atomic< bool > | isRunning_ { false } |
Boolean that specifies if the Manager is already running. More... | |
std::vector< std::shared_ptr< Rokubimini > > | rokubiminis_ |
std::atomic< bool > | shutdownRequested_ { false } |
Boolean that specifies if shutdown has been requested. More... | |
std::shared_ptr< bota_worker::Worker > | updateWorker_ { nullptr } |
A Worker instance that handles the update process. More... | |
Private Attributes | |
std::string | configurationFile_ { "" } |
NodeHandlePtr | nh_ |
bool | standalone_ { true } |
double | timeStep_ { 0.0 } |
The Rokubimini Manager class.
A class that provides a general implementation of a Manager for the Rokubimini devices. It implements the base functionalities from its parent (load, startup, update, shutdown) and provides a generic and medium-ignorant way of doing so.
Definition at line 105 of file Manager.hpp.
|
delete |
rokubimini::RokubiminiManager::RokubiminiManager | ( | const bool | standalone, |
const bool | installSignalHandler, | ||
const double | timeStep = 0.01 , |
||
const NodeHandlePtr | nh = nullptr |
||
) |
Custom constructor. The default constructor is deleted.
This method constructs a RokubiminiManager and starts up a Signal Handler upon request.
standalone | Boolean that defines whether the Manager should run as a standalone program. |
installSignalHandler | Boolean that defines whether there will be a signal handler installed. |
timeStep | Boolean that defines the time step between two consecutive updates(?). |
nh | The NodeHandle for accessing the parameter server. |
Definition at line 9 of file Manager.cpp.
|
overridedefault |
|
protected |
Adds a Rokubimini instance to the list.
rokubimini | The Rokubimini instance. |
Definition at line 87 of file Manager.cpp.
|
protected |
Creates an implementation-specific Rokubimini instance (through the rokubimini_factory), loads the RokubiminiSetup to it and adds the new instance to the list.
rokubiminiSetup | The RokubiminiSetup which will be loaded to a new Rokubimini instance. |
void rokubimini::RokubiminiManager::createRokubiminiRosPublishers | ( | ) | const |
Creates ROS Publishers for each attached rokubimini.
Definition at line 117 of file Manager.cpp.
void rokubimini::RokubiminiManager::createRokubiminiRosServices | ( | ) | const |
Creates ROS Services for each attached rokubimini.
Definition at line 124 of file Manager.cpp.
|
protected |
Creates the Rokubimini instances from a Setup.
setup | The Setup needed for creating the Rokubimini instances. |
Definition at line 50 of file Manager.cpp.
std::shared_ptr< Rokubimini > rokubimini::RokubiminiManager::getRokubimini | ( | const std::string & | name | ) | const |
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 18 of file Manager.cpp.
std::vector< std::shared_ptr< Rokubimini > > rokubimini::RokubiminiManager::getRokubiminis | ( | ) | const |
Definition at line 30 of file Manager.cpp.
|
protected |
Handles the signal received. Specifically requests shuts down if the signum is SIGSEGV.
signum | The number of the signal. |
Definition at line 276 of file Manager.cpp.
|
protected |
Calls the loadSetup() of each Bus Manager.
Definition at line 63 of file Manager.cpp.
|
overridevirtual |
Loads the Setup from the parameter server.
This method is used for loading the Setup from the parameter server. It starts by parsing the necessary parameters in the parameter server and acquiring general information for each to-be-set Rokubimini (e.g. name, configuration_file), as well as specific information (e.g. ethercat_bus or port). This process is done through calling functions from the rokubimini_factory which knows the implementation-specific stuff. Then, it creates Rokubiminis based on the implementation-specific information located in the parameter server (by calling again functions) and loads the configuration found in the parameter server which is loaded for each. Finally it calls the relevant BusManager to attach it to the bus. This process is also done through the rokubimini_factory.
setupFile | The file to load the setup from. |
Implements rokubimini::BaseManager.
Definition at line 40 of file Manager.cpp.
void rokubimini::RokubiminiManager::publishRosMessages | ( | ) | const |
Publishes the ROS messages for each attached rokubimini.
Definition at line 131 of file Manager.cpp.
|
protected |
Sets a flag that represents that shutdown has been requested.
Definition at line 271 of file Manager.cpp.
|
protected |
Decides if a specific Rokubimini instance exists in the list.
name | Name to search in the list. |
Definition at line 98 of file Manager.cpp.
void rokubimini::RokubiminiManager::setNodeHandle | ( | const std::shared_ptr< ros::NodeHandle > & | nh | ) | const |
Sets the ROS NodeHandle to each rokubimini.
nh | The ROS NodeHandle |
Definition at line 110 of file Manager.cpp.
|
overridevirtual |
Shuts down everything.
Shuts down all the Rokubimini devices and the buses from their relative BusManagers. Also stops the updateWorker thread that is running in parallel.
Implements rokubimini::BaseManager.
Definition at line 227 of file Manager.cpp.
|
overridevirtual |
Starts the communication with all the Rokubimini devices.
This method starts the communication with all the Rokubimini devices. Also some funcionalities of the BusManagers are called between the startup phases of the Rokubiminis.
Implements rokubimini::BaseManager.
Definition at line 139 of file Manager.cpp.
|
overridevirtual |
Updates with new values from/to the Rokubiminis.
This method updates the Manager with new values (Readings) from the Rokubimini devices. Also there are calls to optional implementation of readAllBuses and writeToAllBuses of each BusManager implementation.
Implements rokubimini::BaseManager.
Definition at line 198 of file Manager.cpp.
void rokubimini::RokubiminiManager::updateCommunicationManagerReadMessages | ( | ) |
Instructs each BusManager to read the messages.
This method allows each BusManager to read the messages created to its attached buses.
Definition at line 205 of file Manager.cpp.
void rokubimini::RokubiminiManager::updateCommunicationManagerWriteMessages | ( | ) |
Instructs each BusManager to write the messages.
This method allows each BusManager to write the messages created to its attached buses.
Definition at line 220 of file Manager.cpp.
void rokubimini::RokubiminiManager::updateProcessReadings | ( | ) |
Gets the Readings from each Rokubimini device.
This method gets the Readings from each Rokubimini device. It calls the updateProcessReading method of each Rokubimini instance.
Definition at line 212 of file Manager.cpp.
|
protected |
Callback method which when triggered calls the update() method.
event | Event triggering the callback. |
Definition at line 267 of file Manager.cpp.
|
protected |
Definition at line 418 of file Manager.hpp.
|
private |
Definition at line 434 of file Manager.hpp.
|
protected |
Boolean that specifies if the Manager is already running.
Definition at line 387 of file Manager.hpp.
|
private |
Definition at line 435 of file Manager.hpp.
|
protected |
Definition at line 407 of file Manager.hpp.
|
protected |
Boolean that specifies if shutdown has been requested.
Definition at line 397 of file Manager.hpp.
|
private |
Definition at line 432 of file Manager.hpp.
|
private |
Definition at line 433 of file Manager.hpp.
|
protected |
A Worker instance that handles the update process.
Definition at line 377 of file Manager.hpp.