Go to the documentation of this file.
5 #include <unordered_map>
9 #include <rokubimini/setup/Rokubimini.hpp>
128 RokubiminiManager(
const bool standalone,
const bool installSignalHandler,
const double timeStep = 0.01,
144 std::shared_ptr<Rokubimini>
getRokubimini(
const std::string& name)
const;
262 void setNodeHandle(
const std::shared_ptr<ros::NodeHandle>& nh)
const;
bool update() override
Updates with new values from/to the Rokubiminis.
std::atomic< bool > shutdownRequested_
Boolean that specifies if shutdown has been requested.
bool updateWorkerCb(const bota_worker::WorkerEvent &event)
Callback method which when triggered calls the update() method.
void createRokubiminiRosPublishers() const
Creates ROS Publishers for each attached rokubimini.
std::string configurationFile_
void updateProcessReadings()
Gets the Readings from each Rokubimini device.
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
void shutdown() override
Shuts down everything.
virtual void shutdown()=0
Shuts down the communication with the devices.
std::vector< std::unique_ptr< RokubiminiBusManager > > busManagers_
void updateCommunicationManagerWriteMessages()
Instructs each BusManager to write the messages.
std::shared_ptr< Rokubimini > getRokubimini(const std::string &name) const
Returns the Rokubimini instance with name name.
std::atomic< bool > isRunning_
Boolean that specifies if the Manager is already running.
void handleSignal(const int signum)
Handles the signal received. Specifically requests shuts down if the signum is SIGSEGV.
virtual bool loadSetup()=0
Loads the Setup.
bool addRokubimini(const std::shared_ptr< Rokubimini > &rokubimini)
Adds a Rokubimini instance to the list.
The Rokubimini Manager class.
bool loadBusManagersSetup()
Calls the loadSetup() of each Bus Manager.
void requestShutdown()
Sets a flag that represents that shutdown has been requested.
bool createRokubiminisFromSetup(const rokubimini::setup::SetupPtr &setup)
Creates the Rokubimini instances from a Setup.
std::shared_ptr< Setup > SetupPtr
void publishRosMessages() const
Publishes the ROS messages for each attached rokubimini.
bool rokubiminiExists(const std::string &name) const
Decides if a specific Rokubimini instance exists in the list.
bool loadSetup() override
Loads the Setup from the parameter server.
std::vector< std::shared_ptr< Rokubimini > > rokubiminis_
bool createAndConfigureRokubimini(const std::shared_ptr< rokubimini::setup::Rokubimini > &rokubiminiSetup)
Creates an implementation-specific Rokubimini instance (through the rokubimini_factory),...
~RokubiminiManager() override=default
virtual ~BaseManager()=default
virtual bool startup()=0
Starts up the communication with the devices.
BaseManager()
Default constructor.
void setNodeHandle(const std::shared_ptr< ros::NodeHandle > &nh) const
Sets the ROS NodeHandle to each rokubimini.
RokubiminiManager()=delete
std::shared_ptr< bota_worker::Worker > updateWorker_
A Worker instance that handles the update process.
void updateCommunicationManagerReadMessages()
Instructs each BusManager to read the messages.
std::vector< std::shared_ptr< Rokubimini > > getRokubiminis() const
void createRokubiminiRosServices() const
Creates ROS Services for each attached rokubimini.
bool startup() override
Starts the communication with all the Rokubimini devices.
virtual bool update()=0
Updates (Readings) the communication with the devices.