BusManager.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 // std
4 #include <memory>
5 #include <mutex>
8 #include <utility>
9 
10 namespace rokubimini
11 {
23 {
24 public:
25  using DiagnosticsUpdaterPtr = std::shared_ptr<diagnostic_updater::Updater>;
26  using NodeHandlePtr = std::shared_ptr<ros::NodeHandle>;
34  RokubiminiBusManager() = delete;
35 
44  explicit RokubiminiBusManager(const std::string& busName, NodeHandlePtr nh)
45  : bota_node::Node(nh), name_(busName), nh_(std::move(nh))
46  {
47  rokubiminis_.clear();
48  };
49 
58  explicit RokubiminiBusManager(const NodeHandlePtr& nh) : bota_node::Node(nh), nh_(nh)
59  {
60  rokubiminis_.clear();
61  };
62 
69  ~RokubiminiBusManager() override = default;
70 
88  virtual bool addRokubiminiToBus(const std::shared_ptr<Rokubimini>& rokubimini) const;
89 
100  virtual bool startupCommunication()
101  {
102  return true;
103  };
104 
113  bool init() override;
114 
123  void cleanup() override;
124 
135  virtual bool startup();
136 
148  virtual bool update(const bota_worker::WorkerEvent& event);
149 
161  virtual void shutdown();
162 
173  virtual void shutdownBus(){ /* do nothing */ };
174 
185  virtual void writeToBus(){ /* do nothing */ };
186 
196  virtual void readBus(){ /* do nothing */ };
197 
208  virtual void setConfigMode(){ /* do nothing */ };
209 
220  virtual void setRunMode(){ /* do nothing */ };
221 
234  virtual bool createRokubimini(const std::string& rokubiminiName) = 0;
235 
242  virtual bool createRokubiminisFromParamServer();
243 
251  virtual bool loadBusParameters() = 0;
252 
259  virtual bool load();
260 
268  inline std::string getName() const
269  {
270  return name_;
271  }
272 
281  void setNodeHandle(const NodeHandlePtr& nh)
282  {
283  nh_ = nh;
284  for (const auto& rokubimini : rokubiminis_)
285  {
286  rokubimini->setNodeHandle(nh);
287  }
288  }
289 
298  inline bool hasRokubimini(const std::string& name)
299  {
300  for (const auto& rokubimini : rokubiminis_)
301  {
302  if (rokubimini->getName() == name)
303  {
304  return true;
305  }
306  }
307  return false;
308  }
309 
321  inline std::shared_ptr<Rokubimini> getRokubimini(const std::string& name) const
322  {
323  for (const auto& rokubimini : rokubiminis_)
324  {
325  if (rokubimini->getName() == name)
326  {
327  return rokubimini;
328  }
329  }
330  return nullptr;
331  }
332 
343  inline std::vector<std::shared_ptr<Rokubimini>> getRokubiminis() const
344  {
345  return rokubiminis_;
346  }
347 
354  inline void createRokubiminiRosPublishers() const
355  {
356  for (const auto& rokubimini : rokubiminis_)
357  {
358  rokubimini->createRosPublishers();
359  }
360  }
361 
368  inline void createRokubiminiRosServices() const
369  {
370  for (const auto& rokubimini : rokubiminis_)
371  {
372  rokubimini->createRosServices();
373  }
374  }
375 
382  inline void createRokubiminiRosDiagnostics() const
383  {
384  for (const auto& rokubimini : rokubiminis_)
385  {
386  rokubimini->createRosDiagnostics();
387  }
388  }
395  inline void publishRosMessages() const
396  {
397  for (const auto& rokubimini : rokubiminis_)
398  {
399  rokubimini->publishRosMessages();
400  }
401  }
408  virtual void publishBusManagerRosDiagnostics() = 0;
409 
417  {
418  for (const auto& rokubimini : rokubiminis_)
419  {
420  rokubimini->publishRosDiagnostics();
421  }
422  }
429  inline void startupWithoutCommunication() const
430  {
431  for (const auto& rokubimini : rokubiminis_)
432  {
433  rokubimini->startupWithoutCommunication();
434  }
435  }
436 
447  inline void shutdownWithoutCommunication() const
448  {
449  for (const auto& rokubimini : rokubiminis_)
450  {
451  rokubimini->shutdownWithoutCommunication();
452  }
453  }
454 
465  inline void shutdownWithCommunication() const
466  {
467  for (const auto& rokubimini : rokubiminis_)
468  {
469  rokubimini->shutdownWithCommunication();
470  }
471  }
472 
481  inline void startupWithCommunication() const
482  {
483  for (const auto& rokubimini : rokubiminis_)
484  {
485  rokubimini->startupWithCommunication();
486  }
487  }
488 
497  inline void updateProcessReading() const
498  {
499  for (const auto& rokubimini : rokubiminis_)
500  {
501  rokubimini->updateProcessReading();
502  }
503  }
504 
512  virtual double loadTimeStep() = 0;
513 
514 protected:
521  std::vector<std::shared_ptr<Rokubimini>> rokubiminis_;
522 
529  std::string name_;
537 
546  std::atomic<bool> isRunning_{ false };
547 };
548 
549 } // namespace rokubimini
rokubimini::RokubiminiBusManager::rokubiminis_
std::vector< std::shared_ptr< Rokubimini > > rokubiminis_
Definition: BusManager.hpp:521
rokubimini::RokubiminiBusManager::publishBusManagerRosDiagnostics
virtual void publishBusManagerRosDiagnostics()=0
Publish the ROS Diagnostics for the Bus Manager. It's virtual since it's implementation specific.
rokubimini::RokubiminiBusManager::startupWithCommunication
void startupWithCommunication() const
Starts up all Rokubimini devices after communication has been established from the Bus Manager.
Definition: BusManager.hpp:481
rokubimini::RokubiminiBusManager::readBus
virtual void readBus()
Reads the bus.
Definition: BusManager.hpp:196
rokubimini::RokubiminiBusManager::publishRosMessages
void publishRosMessages() const
Publishes the ROS messages for each attached rokubimini.
Definition: BusManager.hpp:395
rokubimini::RokubiminiBusManager::loadTimeStep
virtual double loadTimeStep()=0
Loads the time_step from the Parameter Server.
rokubimini::RokubiminiBusManager::name_
std::string name_
The name of the bus.
Definition: BusManager.hpp:529
rokubimini::RokubiminiBusManager::startup
virtual bool startup()
Starts the communication with all the Rokubimini devices.
Definition: BusManager.cpp:47
rokubimini::RokubiminiBusManager::RokubiminiBusManager
RokubiminiBusManager(const NodeHandlePtr &nh)
Constructor with initialization list for the NodeHandle.
Definition: BusManager.hpp:58
rokubimini::RokubiminiBusManager::startupWithoutCommunication
void startupWithoutCommunication() const
Starts up all Rokubimini devices before communication has been established by the Bus Manager.
Definition: BusManager.hpp:429
bota_node::Node::NodeHandlePtr
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
bota_node
rokubimini::RokubiminiBusManager::setRunMode
virtual void setRunMode()
Sets the devices controlled from the BusManager to run mode.
Definition: BusManager.hpp:220
rokubimini::RokubiminiBusManager::publishRokubiminiRosDiagnostics
void publishRokubiminiRosDiagnostics() const
Publishes the ROS Diagnostics for each attached rokubimini.
Definition: BusManager.hpp:416
rokubimini::RokubiminiBusManager::shutdownWithCommunication
void shutdownWithCommunication() const
Shuts down every Rokubimini device after communication has been closed.
Definition: BusManager.hpp:465
rokubimini::RokubiminiBusManager::nh_
NodeHandlePtr nh_
The internal NodeHandle variable.
Definition: BusManager.hpp:536
rokubimini::RokubiminiBusManager::setConfigMode
virtual void setConfigMode()
Sets the devices controlled from the BusManager to config mode.
Definition: BusManager.hpp:208
rokubimini::RokubiminiBusManager::init
bool init() override
Initializes the Bus Manager Node.
Definition: BusManager.hpp:103
rokubimini::RokubiminiBusManager::createRokubiminiRosDiagnostics
void createRokubiminiRosDiagnostics() const
Creates ROS Diagnostics for each attached rokubimini.
Definition: BusManager.hpp:382
rokubimini::RokubiminiBusManager::getRokubiminis
std::vector< std::shared_ptr< Rokubimini > > getRokubiminis() const
Definition: BusManager.hpp:343
rokubimini::RokubiminiBusManager::cleanup
void cleanup() override
Cleans up the Bus Manager Node.
Definition: BusManager.cpp:80
rokubimini::RokubiminiBusManager::update
virtual bool update(const bota_worker::WorkerEvent &event)
Updates with new values from/to the Rokubiminis.
Definition: BusManager.cpp:68
rokubimini::RokubiminiBusManager::DiagnosticsUpdaterPtr
std::shared_ptr< diagnostic_updater::Updater > DiagnosticsUpdaterPtr
Definition: BusManager.hpp:25
rokubimini::RokubiminiBusManager::addRokubiminiToBus
virtual bool addRokubiminiToBus(const std::shared_ptr< Rokubimini > &rokubimini) const
Adds a Rokubimini to Bus.
Definition: BusManager.cpp:98
bota_node::Node::Node
Node()=delete
rokubimini::RokubiminiBusManager::RokubiminiBusManager
RokubiminiBusManager()=delete
Default constructor.
rokubimini::RokubiminiBusManager::shutdownBus
virtual void shutdownBus()
Shuts down the bus.
Definition: BusManager.hpp:173
rokubimini::RokubiminiBusManager::shutdown
virtual void shutdown()
Shuts down everything.
Definition: BusManager.cpp:85
rokubimini
rokubimini::RokubiminiBusManager::writeToBus
virtual void writeToBus()
Writes to the buses.
Definition: BusManager.hpp:185
rokubimini::RokubiminiBusManager::hasRokubimini
bool hasRokubimini(const std::string &name)
Returns true if the rokubimini with name is found.
Definition: BusManager.hpp:298
rokubimini::RokubiminiBusManager::createRokubiminiRosPublishers
void createRokubiminiRosPublishers() const
Creates ROS Publishers for each attached rokubimini.
Definition: BusManager.hpp:354
bota_worker::WorkerEvent
Rokubimini.hpp
rokubimini::RokubiminiBusManager::updateProcessReading
void updateProcessReading() const
Updates all Rokubimini instances with new measurements.
Definition: BusManager.hpp:497
rokubimini::RokubiminiBusManager::createRokubiminiRosServices
void createRokubiminiRosServices() const
Creates ROS Services for each attached rokubimini.
Definition: BusManager.hpp:368
rokubimini::RokubiminiBusManager::loadBusParameters
virtual bool loadBusParameters()=0
Loads bus-specific parameters from parameter server. It's pure virtual since it's implementation-spec...
rokubimini::RokubiminiBusManager::getRokubimini
std::shared_ptr< Rokubimini > getRokubimini(const std::string &name) const
Returns the Rokubimini instance with name name.
Definition: BusManager.hpp:321
rokubimini::RokubiminiBusManager::createRokubiminisFromParamServer
virtual bool createRokubiminisFromParamServer()
Creates rokubiminis from the parameter server.
Definition: BusManager.cpp:117
rokubimini::RokubiminiBusManager::startupCommunication
virtual bool startupCommunication()
Starts the communication through the bus.
Definition: BusManager.hpp:100
rokubimini::RokubiminiBusManager::load
virtual bool load()
Loads the configuration of the bus (bus parameters and rokubiminis).
Definition: BusManager.cpp:102
std
rokubimini::RokubiminiBusManager
The Rokubimini Bus Manager class.
Definition: BusManager.hpp:22
rokubimini::RokubiminiBusManager::setNodeHandle
void setNodeHandle(const NodeHandlePtr &nh)
Sets the nodeHandle of the device.
Definition: BusManager.hpp:281
rokubimini::RokubiminiBusManager::createRokubimini
virtual bool createRokubimini(const std::string &rokubiminiName)=0
Creates an implementation-specific Rokubimini instance.
Definition: BusManager.hpp:220
bota_node::Node
rokubimini::RokubiminiBusManager::RokubiminiBusManager
RokubiminiBusManager(const std::string &busName, NodeHandlePtr nh)
Constructor with initialization list for the name and NodeHandle.
Definition: BusManager.hpp:44
bota_node.hpp
rokubimini::RokubiminiBusManager::shutdownWithoutCommunication
void shutdownWithoutCommunication() const
Definition: BusManager.hpp:447
rokubimini::RokubiminiBusManager::isRunning_
std::atomic< bool > isRunning_
Boolean that specifies if the Manager is already running.
Definition: BusManager.hpp:546
rokubimini::RokubiminiBusManager::~RokubiminiBusManager
~RokubiminiBusManager() override=default
Default Destructor.
Definition: BusManager.hpp:61
rokubimini::RokubiminiBusManager::getName
std::string getName() const
Gets the name of the bus.
Definition: BusManager.hpp:268


rokubimini_bus_manager
Author(s):
autogenerated on Sat Apr 15 2023 02:53:54