83 error_recovered_cb.second(
getName());
106 fatal_recovered_cb.second(
getName());
122 device_disconnected_cb.second(
getName());
156 reading_cb.second(
getName(), reading);
165 device_reconnected_cb.second(
getName());
193 std::vector<std::string> infos;
194 std::vector<std::string> warnings;
195 std::vector<std::string> errors;
196 std::vector<std::string> fatals;
198 for (
const std::string& info : infos)
202 for (
const std::string& warning : warnings)
206 for (
const std::string& error : errors)
210 for (
const std::string& fatal : fatals)
bool hasForceTorqueOffset() const
Checks if the value of the forceTorqueOffset_ variable has been set by the user in the configuration ...
bool hasImuAccelerationRange() const
Checks if the value of the imuAccelerationRange_ variable has been set by the user in the configurati...
bool deviceIsInErrorState()
Checks if the device is in error state.
bool hasForceTorqueFilter() const
Checks if the value of the forceTorqueFilter_ variable has been set by the user in the configuration ...
bool hasSensorCalibration() const
Checks if the value of the sensorCalibration_ variable has been set by the user in the configuration ...
const WrenchType & getWrench() const
Gets the wrench variable.
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.
Statusword statusword_
The current statusword.
const ForceTorqueFilter & getForceTorqueFilter() const
Gets the forceTorqueFilter variable.
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.
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.
bool hasImuAngularRateFilter() const
Checks if the value of the imuAngularRateFilter_ variable has been set by the user in the configurati...
virtual bool setAccelerationRange(const unsigned int range)=0
Sets an acceleration range to the device. It's virtual since 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.
bool hasSensorConfiguration() const
Checks if the value of the sensorConfiguration_ variable has been set by the user in the configuratio...
Class representing the readings received from the rokubi mini devices.
void clearGoalStateEnum()
Clears the goal state enumeration.
const Eigen::Matrix< double, 6, 1 > & getForceTorqueOffset() const
Gets the forceTorqueOffset variable.
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.
bool hasImuAngularRateRange() const
Checks if the value of the imuAngularRateRange_ variable has been set by the user in the configuratio...
bool isEmpty() const
Checks whether the statusword is empty.
bool getUseCustomCalibration() const
Gets the useCustomCalibration variable.
uint32_t getData() const
Gets the data variable.
void getMessagesDiff(Statusword &previousStatusword, std::vector< std::string > &infos, std::vector< std::string > &warnings, std::vector< std::string > &errors, std::vector< std::string > &fatals) const
Gets the different messages form the previous statusword.
bool getSaveConfiguration() const
Gets the saveConfiguration variable.
unsigned int getImuAngularRateFilter() const
Gets the imuAccelerationFilter variable.
std::string getName() const
Gets the name of the device.
bool hasSaveConfiguration() const
Checks if the value of the saveConfiguration_ variable has been set by the user in the configuration ...
std::multimap< int, DeviceReconnectedCb, std::greater< int > > deviceReconnectedCbs_
uint8_t getImuAccelerationRange() const
Gets the imuAccelerationRange variable.
configuration::Configuration configuration_
The Configuration of the device.
void deviceReconnectedCb()
Calls the callbacks in the device reconnected callbacks list.
void setStatusword(const Statusword &statusword)
Sets the statusword variable.
const calibration::SensorCalibration & getSensorCalibration() const
Gets the sensorCalibration variable.
unsigned int getImuAccelerationFilter() const
uint8_t getImuAngularRateRange() const
Gets the imuAngularRateRange variable.
TimePoint getStamp() const
Gets the stamp variable.
void errorCb()
Calls the callbacks in the error callbacks list.
std::atomic< bool > statuswordRequested_
Flag indicating if a statusword has been actively requested.
std::multimap< int, ErrorCb, std::greater< int > > errorCbs_
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
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.
Reading getReading() const
Gets the reading from the Rokubimini device.
std::multimap< int, ErrorRecoveredCb, std::greater< int > > errorRecoveredCbs_
#define ROS_INFO_STREAM(args)
virtual bool setAccelerationFilter(const unsigned int filter)=0
Sets an acceleration filter to the device. It's virtual since it's implementation-specific.
bool hasImuAccelerationFilter() const
Checks if the value of the imuAccelerationFilter_ variable has been set by the user in the configurat...
void fatalRecoveredCb()
Calls the callbacks in the fatal recovered callbacks list.
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.
#define ROS_ERROR_STREAM(args)
const SensorConfiguration & getSensorConfiguration() const
Gets the sensorConfiguration variable.
configuration::Configuration & getConfiguration()
Non-const version of getConfiguration() const. Gets the Configuration of the device.
std::string name_
The name of the device.
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.
const ImuType & getImu() const
Gets the imu variable.
virtual bool setSensorConfiguration(const configuration::SensorConfiguration &sensorConfiguration)=0
Sets a sensor configuration to the device. It's virtual since it's implementation-specific.