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;
157 std::vector<std::shared_ptr<Rokubimini>> getRokubiminis()
const;
229 void updateProcessReadings();
241 void updateCommunicationManagerWriteMessages();
252 void updateCommunicationManagerReadMessages();
262 void setNodeHandle(
const std::shared_ptr<ros::NodeHandle>& nh)
const;
271 void createRokubiminiRosPublishers()
const;
280 void createRokubiminiRosServices()
const;
288 void publishRosMessages()
const;
299 bool addRokubimini(
const std::shared_ptr<Rokubimini>&
rokubimini);
310 bool rokubiminiExists(
const std::string& name)
const;
354 bool loadBusManagersSetup();
367 bool createAndConfigureRokubimini(
const std::shared_ptr<rokubimini::setup::Rokubimini>& rokubiminiSetup);
377 std::shared_ptr<bota_worker::Worker> updateWorker_{
nullptr };
387 std::atomic<bool> isRunning_{
false };
397 std::atomic<bool> shutdownRequested_{
false };
429 void handleSignal(
const int signum);
432 bool standalone_{
true };
433 double timeStep_{ 0.0 };
434 std::string configurationFile_{
"" };
virtual void shutdown()=0
Shuts down the communication with the devices.
The Rokubimini Manager class.
virtual ~BaseManager()=default
virtual bool loadSetup()=0
Loads the Setup.
virtual bool startup()=0
Starts up the communication with the devices.
std::vector< std::unique_ptr< RokubiminiBusManager > > busManagers_
std::vector< std::shared_ptr< Rokubimini > > rokubiminis_
std::shared_ptr< Setup > SetupPtr
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
virtual bool update()=0
Updates (Readings) the communication with the devices.
ROSCPP_DECL void requestShutdown()
BaseManager()
Default constructor.