Go to the documentation of this file.
113 bool init()
override;
321 inline std::shared_ptr<Rokubimini>
getRokubimini(
const std::string& name)
const
std::vector< std::shared_ptr< Rokubimini > > rokubiminis_
virtual void publishBusManagerRosDiagnostics()=0
Publish the ROS Diagnostics for the Bus Manager. It's virtual since it's implementation specific.
void startupWithCommunication() const
Starts up all Rokubimini devices after communication has been established from the Bus Manager.
virtual void readBus()
Reads the bus.
void publishRosMessages() const
Publishes the ROS messages for each attached rokubimini.
virtual double loadTimeStep()=0
Loads the time_step from the Parameter Server.
std::string name_
The name of the bus.
virtual bool startup()
Starts the communication with all the Rokubimini devices.
RokubiminiBusManager(const NodeHandlePtr &nh)
Constructor with initialization list for the NodeHandle.
void startupWithoutCommunication() const
Starts up all Rokubimini devices before communication has been established by the Bus Manager.
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
virtual void setRunMode()
Sets the devices controlled from the BusManager to run mode.
void publishRokubiminiRosDiagnostics() const
Publishes the ROS Diagnostics for each attached rokubimini.
void shutdownWithCommunication() const
Shuts down every Rokubimini device after communication has been closed.
NodeHandlePtr nh_
The internal NodeHandle variable.
virtual void setConfigMode()
Sets the devices controlled from the BusManager to config mode.
bool init() override
Initializes the Bus Manager Node.
void createRokubiminiRosDiagnostics() const
Creates ROS Diagnostics for each attached rokubimini.
std::vector< std::shared_ptr< Rokubimini > > getRokubiminis() const
void cleanup() override
Cleans up the Bus Manager Node.
virtual bool update(const bota_worker::WorkerEvent &event)
Updates with new values from/to the Rokubiminis.
std::shared_ptr< diagnostic_updater::Updater > DiagnosticsUpdaterPtr
virtual bool addRokubiminiToBus(const std::shared_ptr< Rokubimini > &rokubimini) const
Adds a Rokubimini to Bus.
RokubiminiBusManager()=delete
Default constructor.
virtual void shutdownBus()
Shuts down the bus.
virtual void shutdown()
Shuts down everything.
virtual void writeToBus()
Writes to the buses.
bool hasRokubimini(const std::string &name)
Returns true if the rokubimini with name is found.
void createRokubiminiRosPublishers() const
Creates ROS Publishers for each attached rokubimini.
void updateProcessReading() const
Updates all Rokubimini instances with new measurements.
void createRokubiminiRosServices() const
Creates ROS Services for each attached rokubimini.
virtual bool loadBusParameters()=0
Loads bus-specific parameters from parameter server. It's pure virtual since it's implementation-spec...
std::shared_ptr< Rokubimini > getRokubimini(const std::string &name) const
Returns the Rokubimini instance with name name.
virtual bool createRokubiminisFromParamServer()
Creates rokubiminis from the parameter server.
virtual bool startupCommunication()
Starts the communication through the bus.
virtual bool load()
Loads the configuration of the bus (bus parameters and rokubiminis).
The Rokubimini Bus Manager class.
void setNodeHandle(const NodeHandlePtr &nh)
Sets the nodeHandle of the device.
virtual bool createRokubimini(const std::string &rokubiminiName)=0
Creates an implementation-specific Rokubimini instance.
RokubiminiBusManager(const std::string &busName, NodeHandlePtr nh)
Constructor with initialization list for the name and NodeHandle.
void shutdownWithoutCommunication() const
std::atomic< bool > isRunning_
Boolean that specifies if the Manager is already running.
~RokubiminiBusManager() override=default
Default Destructor.
std::string getName() const
Gets the name of the bus.