Manager.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <vector>
4 #include <mutex>
5 #include <unordered_map>
6 #include <bota_worker/Worker.hpp>
7 
9 #include <rokubimini/setup/Rokubimini.hpp>
10 
13 using NodeHandlePtr = std::shared_ptr<ros::NodeHandle>;
14 namespace rokubimini
15 {
29 {
30 public:
40 
41  virtual ~BaseManager() = default;
42 
53  virtual bool loadSetup() = 0;
54 
65  virtual bool startup() = 0;
66 
77  virtual bool update() = 0;
78 
88  virtual void shutdown() = 0;
89 };
90 
106 {
107 public:
108  RokubiminiManager() = delete;
109 
128  RokubiminiManager(const bool standalone, const bool installSignalHandler, const double timeStep = 0.01,
129  const NodeHandlePtr nh = nullptr);
130 
131  ~RokubiminiManager() override = default;
132 
144  std::shared_ptr<Rokubimini> getRokubimini(const std::string& name) const;
145 
157  std::vector<std::shared_ptr<Rokubimini>> getRokubiminis() const;
158 
176  bool loadSetup() override;
177 
189  bool startup() override;
190 
203  bool update() override;
204 
217  void shutdown() override;
218 
229  void updateProcessReadings();
230 
241  void updateCommunicationManagerWriteMessages();
242 
252  void updateCommunicationManagerReadMessages();
253 
262  void setNodeHandle(const std::shared_ptr<ros::NodeHandle>& nh) const;
263 
271  void createRokubiminiRosPublishers() const;
272 
280  void createRokubiminiRosServices() const;
281 
288  void publishRosMessages() const;
289 
290 protected:
299  bool addRokubimini(const std::shared_ptr<Rokubimini>& rokubimini);
300 
310  bool rokubiminiExists(const std::string& name) const;
311 
323  bool updateWorkerCb(const bota_worker::WorkerEvent& event);
324 
334  void requestShutdown();
335 
345  bool createRokubiminisFromSetup(const rokubimini::setup::SetupPtr& setup);
346 
354  bool loadBusManagersSetup();
355 
367  bool createAndConfigureRokubimini(const std::shared_ptr<rokubimini::setup::Rokubimini>& rokubiminiSetup);
368 
377  std::shared_ptr<bota_worker::Worker> updateWorker_{ nullptr };
378 
387  std::atomic<bool> isRunning_{ false };
388 
397  std::atomic<bool> shutdownRequested_{ false };
398 
407  std::vector<std::shared_ptr<Rokubimini>> rokubiminis_;
408  // std::unordered_map<std::unique_ptr<RokubiminiBusManager>, std::vector<std::unique_ptr<Rokubimini>>>
409  // mapOfRokubiminisToBusManagers_;
410 
418  std::vector<std::unique_ptr<RokubiminiBusManager>> busManagers_;
419 
429  void handleSignal(const int signum);
430 
431 private:
432  bool standalone_{ true };
433  double timeStep_{ 0.0 };
434  std::string configurationFile_{ "" };
436 };
437 } // namespace rokubimini
virtual void shutdown()=0
Shuts down the communication with the devices.
The Rokubimini Manager class.
Definition: Manager.hpp:105
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_
Definition: Manager.hpp:418
std::vector< std::shared_ptr< Rokubimini > > rokubiminis_
Definition: Manager.hpp:407
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.
Definition: Manager.hpp:39
The Base Manager class.
Definition: Manager.hpp:28


rokubimini_manager
Author(s):
autogenerated on Wed Mar 3 2021 03:09:21