29 using ReadingCb = std::function<void(const std::string&, const Reading&)>;
30 using ErrorCb = std::function<void(const std::string&)>;
32 using FatalCb = std::function<void(const std::string&)>;
564 static constexpr
double NAN_VALUE = std::numeric_limits<double>::quiet_NaN();
636 std::multimap<int, ErrorCb, std::greater<int>>
errorCbs_;
652 std::multimap<int, FatalCb, std::greater<int>>
fatalCbs_;
virtual void updateProcessReading()=0
Updates the Rokubimini object with new measurements.
Class holding the force-torque filter settings.
virtual bool deviceIsMissing() const =0
Checks if the device is missing.
virtual bool getForceTorqueSamplingRate(int &samplingRate)=0
Gets the force torque sampling rate of the device. It's virtual since it's implementation-specific.
Class representing a rokubi mini device.
bool deviceIsInErrorState()
Checks if the device is in error state.
Class holding the configuration of the sensor.
std::multimap< int, FatalRecoveredCb, std::greater< int > > fatalRecoveredCbs_
virtual bool setSensorCalibration(const calibration::SensorCalibration &sensorCalibration)=0
Sets a sensor calibration to the device. It's virtual since it's implementation-specific.
void deviceDisconnectedCb()
Calls the callbacks in the device disconnected callbacks list.
std::function< void(const std::string &)> DeviceReconnectedCb
Statusword statusword_
The current statusword.
bool deviceIsInFatalState()
Checks if the device is in fatal state.
void setStatusword(Statusword &statusword)
Sets the statusword of the device.
static constexpr double NAN_VALUE
NaN abbreviation for convenience.
std::function< void(const std::string &)> FatalCb
std::function< void(const std::string &)> ErrorCb
virtual bool setForceTorqueFilter(const configuration::ForceTorqueFilter &filter)=0
Sets a force torque filter to the device. It's virtual since it's implementation-specific.
void errorRecoveredCb()
Calls the callbacks in the error recovered callbacks list.
bool loadRokubiminiSetup(std::shared_ptr< rokubimini::setup::Rokubimini > setup)
Loads the configuration of the device from the {Rokubimini Setup} provided.
std::function< void(const std::string &)> FatalRecoveredCb
NodeHandlePtr nh_
The node handle of the ROS node, used by the publishers.
virtual bool setAccelerationRange(const unsigned int range)=0
Sets an acceleration range to the device. It's virtual since it's implementation-specific.
virtual void createRosServices()=0
Creates ROS services for the rokubimini device. It's virtual because it's implementation specific...
std::multimap< int, FatalCb, std::greater< int > > fatalCbs_
virtual bool setAngularRateRange(const unsigned int range)=0
Sets an angular rate range to the device. It's virtual since it's implementation-specific.
Class representing the readings received from the rokubi mini devices.
void clearGoalStateEnum()
Clears the goal state enumeration.
Class representing the different states the communication or the sensors can be in.
void startupWithoutCommunication()
Starts up a Rokubimini device before communication has been established by the BusManager.
std::function< void(const std::string &, const Reading &)> ReadingCb
virtual ~Rokubimini()=default
const configuration::Configuration & getConfiguration() const
Gets the Configuration of the device.
Statusword getStatusword() const
Gets the statusword of the device.
std::string getName() const
Gets the name of the device.
Class holding the sensor configuration settings.
The SensorCalibration class is used for holding the calibration information of each rokubi mini senso...
std::multimap< int, DeviceReconnectedCb, std::greater< int > > deviceReconnectedCbs_
virtual void shutdownWithoutCommunication()
configuration::Configuration configuration_
The Configuration of the device.
void addErrorRecoveredCb(const ErrorRecoveredCb &errorRecoveredCb, const int priority=0)
Adds an error recovered callback to a list.
std::function< void(const Reading &)> AnonymousReadingCb
void deviceReconnectedCb()
Calls the callbacks in the device reconnected callbacks list.
void addErrorCb(const ErrorCb &errorCb, const int priority=0)
Adds an error callback to a list.
virtual void publishRosMessages()=0
Publishes ROS messages with data from the rokubimini device. It's virtual because it's implementation...
void errorCb()
Calls the callbacks in the error callbacks list.
void addFatalRecoveredCb(const FatalRecoveredCb &fatalRecoveredCb, const int priority=0)
Adds an fatal recovered callback to a list.
std::atomic< bool > statuswordRequested_
Flag indicating if a statusword has been actively requested.
std::multimap< int, ErrorCb, std::greater< int > > errorCbs_
std::multimap< int, DeviceDisconnectedCb, std::greater< int > > deviceDisconnectedCbs_
void fatalCb()
Calls the callbacks in the fatal callbacks list.
Reading reading_
The reading of the device.
void setNodeHandle(const NodeHandlePtr &nh)
Sets the nodeHandle of the device.
Reading getReading() const
Gets the reading from the Rokubimini device.
void addFatalCb(const FatalCb &fatalCb, const int priority=0)
Adds an fatal callback to a list.
void addDeviceDisconnectedCb(const DeviceDisconnectedCb &deviceDisconnectedCb, const int priority=0)
Adds a device disconnencted callback to a list.
std::multimap< int, ErrorRecoveredCb, std::greater< int > > errorRecoveredCbs_
virtual bool setAccelerationFilter(const unsigned int filter)=0
Sets an acceleration filter to the device. It's virtual since it's implementation-specific.
std::function< void(const std::string &)> DeviceDisconnectedCb
void addDeviceReconnectedCb(const DeviceReconnectedCb &deviceReconnectedCb, const int priority=0)
Adds a device reconnected callback to a list.
void fatalRecoveredCb()
Calls the callbacks in the fatal recovered callbacks list.
virtual void shutdownWithCommunication()=0
Shuts down a Rokubimini device before communication has been closed.
void startupWithCommunication()
Starts up a Rokubimini device after communication has been established.
virtual void doStartupWithCommunication()=0
std::multimap< int, ReadingCb, std::greater< int > > readingCbs_
virtual bool setAngularRateFilter(const unsigned int filter)=0
Sets an angular rate filter to the device. It's virtual since it's implementation-specific.
virtual bool setForceTorqueOffset(const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset)=0
Sets a force torque offset to the device. It's virtual since it's implementation-specific.
virtual bool getSerialNumber(unsigned int &serialNumber)=0
Gets the serial number of the device. It's virtual since it's implementation-specific.
void addReadingCb(const ReadingCb &readingCb, const int priority=0)
Adds a reading callback to a list.
configuration::Configuration & getConfiguration()
Non-const version of getConfiguration() const. Gets the Configuration of the device.
std::string name_
The name of the device.
std::function< void(const std::string &)> ErrorRecoveredCb
virtual bool saveConfigParameter()=0
Saves the current configuration to the device. It's virtual since it's implementation-specific.
std::recursive_mutex readingMutex_
The mutex for accessing the reading.
virtual void createRosPublishers()=0
Creates ROS publishers for the rokubimini device. It's virtual because it's implementation specific...
virtual bool setSensorConfiguration(const configuration::SensorConfiguration &sensorConfiguration)=0
Sets a sensor configuration to the device. It's virtual since it's implementation-specific.
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
Rokubimini()=default
Default constructor.
std::function< void(void)> AnonymousErrorCb