Go to the documentation of this file.
11 : rokubiminis_(), busManagers_(), standalone_(standalone), timeStep_(timeStep), nh_(
std::move(nh))
13 if (installSignalHandler)
32 std::vector<std::shared_ptr<Rokubimini>> rokubimini_out;
38 return rokubimini_out;
53 for (
const auto& rokubimini_setup :
setup->rokubiminis_)
72 bool RokubiminiManager::RokubiminiManager::createAndConfigureRokubimini(
73 const std::shared_ptr<rokubimini::setup::Rokubimini>& rokubiminiSetup)
76 if (!
rokubimini->loadRokubiminiSetup(rokubiminiSetup))
89 const std::string name =
rokubimini->getName();
92 ROS_ERROR_STREAM(
"Cannot add Rokubimini with name '" << name <<
"', because it already exists.");
143 ROS_WARN_STREAM(
"Cannot start up, Rokubimini Manager is already running.");
149 throw ros::Exception(
"Cannot start up, a communication manager has not been set.");
157 if (!bus_manager_ptr->startupCommunication())
161 for (
const auto& rokubimini_setup : bus_manager_ptr->getRokubiminiSetups())
171 bus_manager_ptr->setConfigMode();
179 bus_manager_ptr->setRunMode();
186 update_worker_options.
name_ =
"RokubiminiManager::updateWorker";
209 bus_manager_ptr->readAllBuses();
224 bus_manager_ptr->writeToAllBuses();
231 ROS_WARN_STREAM(
"Cannot shut down, Rokubimini Manager is not running.");
241 update_worker_options.
name_ =
"RokubiminiManager::updateWorker (shutdown)";
258 bus_manager_ptr->shutdownAllBuses();
278 ROS_INFO_STREAM(
"Received signal (" << signum <<
"), requesting shutdown ...");
280 if (signum == SIGSEGV)
282 signal(signum, SIG_DFL);
283 kill(getpid(), signum);
bool update() override
Updates with new values from/to the Rokubiminis.
std::atomic< bool > enforceRate_
#define ROS_ERROR_STREAM(args)
rokubimini::setup::SetupPtr loadBusSetup(std::vector< std::unique_ptr< RokubiminiBusManager >> &busManagers, const NodeHandlePtr &nh)
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.
void updateProcessReadings()
Gets the Readings from each Rokubimini device.
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
void shutdown() override
Shuts down everything.
#define ROS_DEBUG_STREAM(args)
std::vector< std::unique_ptr< RokubiminiBusManager > > busManagers_
void updateCommunicationManagerWriteMessages()
Instructs each BusManager to write the messages.
#define ROS_WARN_STREAM(args)
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.
std::shared_ptr< rokubimini::Rokubimini > createRokubiminiFactory(const std::shared_ptr< rokubimini::setup::Rokubimini > &rokubiminiSetup, const NodeHandlePtr &nh)
bool addRokubimini(const std::shared_ptr< Rokubimini > &rokubimini)
Adds a Rokubimini instance to the list.
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.
#define ROS_INFO_STREAM(args)
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),...
std::atomic< double > timeStep_
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.