BusManager.cpp
Go to the documentation of this file.
1 
3 
4 namespace rokubimini
5 {
7 {
8  std::string setup_file;
9 
10  name_ = ros::this_node::getName().substr(1);
11  if (!load())
12  {
13  ROS_ERROR("[%s] Could not load bus configuration", name_.c_str());
14  return false;
15  }
16 
17  if (!startup())
18  {
19  ROS_WARN("[%s] Bus Manager could not startup", name_.c_str());
20  return false;
21  }
25  std::vector<std::shared_ptr<Rokubimini>> rokubiminis;
26  if (getRokubiminis().empty())
27  {
28  ROS_ERROR("[%s] No rokubimini available", name_.c_str());
29  return false;
30  }
32  options.callback_ = std::bind(&RokubiminiBusManager::update, this, std::placeholders::_1);
33  options.defaultPriority_ = 10; // this has high priority
34  options.name_ = "RokubiminiBusManager::updateWorker";
35  options.timeStep_ = loadTimeStep();
36  if (options.timeStep_ != 0)
37  {
38  if (!this->addWorker(options))
39  {
40  ROS_ERROR_STREAM("[RokubiminiBusManager] Worker " << options.name_ << "could not be added!");
41  return false;
42  }
43  }
44  return true;
45 }
46 
48 {
49  if (isRunning_)
50  {
51  ROS_WARN_STREAM("Cannot start up, Rokubimini Bus Manager is already running.");
52  return false;
53  }
54  ROS_DEBUG_STREAM("Starting up Rokubimini Bus Manager ...");
56  if (!startupCommunication())
57  {
59  return false;
60  }
61  setConfigMode();
63  setRunMode();
64  isRunning_ = true;
65  return true;
66 }
67 
69 {
70  ROS_DEBUG("[RokubiminiBusManager]: update called");
71  readBus();
73  writeToBus();
77  return true;
78 }
79 
81 {
82  shutdown();
83 }
84 
86 {
87  if (!isRunning_)
88  {
89  ROS_WARN_STREAM("Cannot shut down, Rokubimini Bus Manager is not running.");
90  return;
91  }
93  shutdownBus();
95  isRunning_ = false;
96 }
97 
98 bool RokubiminiBusManager::addRokubiminiToBus(const std::shared_ptr<Rokubimini>& rokubimini) const
99 {
100  return true;
101 };
103 {
104  if (!loadBusParameters())
105  {
106  ROS_ERROR("[%s] Could not load bus parameters", name_.c_str());
107  return false;
108  }
110  {
111  ROS_ERROR("[%s] Could not create rokubiminis from parameter server", name_.c_str());
112  return false;
113  }
114  return true;
115 }
116 
118 {
119  std::vector<std::string> keys;
120  std::string rokubimini_name;
121  nh_->getParamNames(keys);
122  for (const auto& key : keys)
123  {
124  // append only parameter names with "/bus_name/rokubiminis" and have "/name"
125  if (key.find(nh_->getNamespace() + "/rokubiminis") != std::string::npos && key.find("/name") != std::string::npos)
126  {
127  nh_->getParam(key, rokubimini_name);
128  ROS_DEBUG("[%s] Key is: %s and name is: %s", name_.c_str(), key.c_str(), rokubimini_name.c_str());
129  if (!createRokubimini(rokubimini_name))
130  {
131  ROS_ERROR("[%s] Could not create rokubimini", name_.c_str());
132  return false;
133  };
134  ROS_DEBUG("[%s] Successfully created rokubimini with name: %s", name_.c_str(), rokubimini_name.c_str());
135  }
136  }
137  return true;
138 }
139 } // namespace rokubimini
rokubimini::RokubiminiBusManager::publishBusManagerRosDiagnostics
virtual void publishBusManagerRosDiagnostics()=0
Publish the ROS Diagnostics for the Bus Manager. It's virtual since it's implementation specific.
bota_worker::RateOptions::name_
std::string name_
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
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
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
BusManager.hpp
rokubimini::RokubiminiBusManager::startupWithoutCommunication
void startupWithoutCommunication() const
Starts up all Rokubimini devices before communication has been established by the Bus Manager.
Definition: BusManager.hpp:429
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
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
rokubimini::RokubiminiBusManager::createRokubiminiRosDiagnostics
void createRokubiminiRosDiagnostics() const
Creates ROS Diagnostics for each attached rokubimini.
Definition: BusManager.hpp:382
bota_worker::WorkerOptions::defaultPriority_
int defaultPriority_
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
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
rokubimini::RokubiminiBusManager::addRokubiminiToBus
virtual bool addRokubiminiToBus(const std::shared_ptr< Rokubimini > &rokubimini) const
Adds a Rokubimini to Bus.
Definition: BusManager.cpp:98
ROS_DEBUG
#define ROS_DEBUG(...)
bota_worker::WorkerOptions::callback_
WorkerCallback callback_
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
bota_worker::WorkerOptions
ROS_WARN
#define ROS_WARN(...)
rokubimini::RokubiminiBusManager::writeToBus
virtual void writeToBus()
Writes to the buses.
Definition: BusManager.hpp:185
rokubimini::RokubiminiBusManager::createRokubiminiRosPublishers
void createRokubiminiRosPublishers() const
Creates ROS Publishers for each attached rokubimini.
Definition: BusManager.hpp:354
bota_worker::WorkerEvent
rokubimini::RokubiminiBusManager::updateProcessReading
void updateProcessReading() const
Updates all Rokubimini instances with new measurements.
Definition: BusManager.hpp:497
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
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::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
bota_worker::RateOptions::timeStep_
std::atomic< double > timeStep_
rokubimini::RokubiminiBusManager::load
virtual bool load()
Loads the configuration of the bus (bus parameters and rokubiminis).
Definition: BusManager.cpp:102
ROS_ERROR
#define ROS_ERROR(...)
rokubimini::RokubiminiBusManager::createRokubimini
virtual bool createRokubimini(const std::string &rokubiminiName)=0
Creates an implementation-specific Rokubimini instance.
Definition: BusManager.hpp:220
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
bota_node::Node::addWorker
bool addWorker(const bota_worker::WorkerOptions &options)


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