Go to the documentation of this file.
10 std::string prefix =
"rokubiminis/" +
name_;
11 std::string product_name_string = prefix +
"/product_name";
12 if (
nh_->hasParam(product_name_string))
18 ROS_ERROR(
"Could not find product name in Parameter Server: %s", product_name_string.c_str());
93 error_recovered_cb.second(
getName());
116 fatal_recovered_cb.second(
getName());
132 device_disconnected_cb.second(
getName());
166 reading_cb.second(
getName(), reading);
175 device_reconnected_cb.second(
getName());
203 std::vector<std::string> infos;
204 std::vector<std::string> warnings;
205 std::vector<std::string> errors;
206 std::vector<std::string> fatals;
208 for (
const std::string& info : infos)
212 for (
const std::string& warning : warnings)
216 for (
const std::string& error : errors)
220 for (
const std::string& fatal : fatals)
uint32_t getData() const
Gets the data variable.
virtual bool setAngularRateFilter(const unsigned int filter)=0
Sets an angular rate filter to the device. It's virtual since it's implementation-specific.
bool deviceIsInErrorState()
Checks if the device is in error state.
void startupWithoutCommunication()
Starts up a Rokubimini device before communication has been established by the BusManager.
unsigned int getImuAccelerationFilter() const
bool hasImuAccelerationRange() const
Checks if the value of the imuAccelerationRange_ variable has been set by the user in the configurati...
std::atomic< bool > statuswordRequested_
Flag indicating if a statusword has been actively requested.
#define ROS_ERROR_STREAM(args)
configuration::Configuration & getConfiguration()
Non-const version of getConfiguration() const. Gets the Configuration of the device.
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.
Reading reading_
The reading of the device.
void setStatusword(const Statusword &statusword)
Sets the statusword variable.
bool getUseCustomCalibration() const
Gets the useCustomCalibration variable.
virtual bool setAccelerationFilter(const unsigned int filter)=0
Sets an acceleration filter to the device. It's virtual since it's implementation-specific.
virtual void load()
Loads the rokubimini configuration from the parameter server.
const ForceTorqueFilter & getForceTorqueFilter() const
Gets the forceTorqueFilter variable.
const ImuType & getImu() const
Gets the imu variable.
std::string getName() const
Gets the name of the device.
void errorRecoveredCb()
Calls the callbacks in the error recovered callbacks list.
uint8_t getImuAccelerationRange() const
Gets the imuAccelerationRange variable.
void fatalRecoveredCb()
Calls the callbacks in the fatal recovered callbacks list.
virtual void postSetupConfiguration()=0
Post-setup configuration hook.
void startupWithCommunication()
Starts up a Rokubimini device after communication has been established.
const WrenchType & getWrench() const
Gets the wrench variable.
virtual bool setForceTorqueFilter(const configuration::ForceTorqueFilter &filter)=0
Sets a force torque filter to the device. It's virtual since it's implementation-specific.
bool hasForceTorqueOffset() const
Checks if the value of the forceTorqueOffset_ variable has been set by the user in the configuration ...
Reading getReading() const
Gets the reading from the Rokubimini device.
void fatalCb()
Calls the callbacks in the fatal callbacks list.
unsigned int getImuAngularRateFilter() const
Gets the imuAccelerationFilter variable.
#define ROS_DEBUG_STREAM(args)
std::string productName_
The product name of the rokubimini.
void load(const std::string &key, const NodeHandlePtr &nh)
Loads the configuration from the parameter server.
Class representing the readings received from the rokubi mini devices.
bool hasForceTorqueFilter() const
Checks if the value of the forceTorqueFilter_ variable has been set by the user in the configuration ...
#define ROS_WARN_STREAM(args)
bool isEmpty() const
Checks whether the statusword is empty.
std::string name_
The name of the device.
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.
std::multimap< int, FatalCb, std::greater< int > > fatalCbs_
const Eigen::Matrix< double, 6, 1 > & getForceTorqueOffset() const
Gets the forceTorqueOffset variable.
bool hasSensorConfiguration() const
Checks if the value of the sensorConfiguration_ variable has been set by the user in the configuratio...
void deviceDisconnectedCb()
Calls the callbacks in the device disconnected callbacks list.
bool hasImuAccelerationFilter() const
Checks if the value of the imuAccelerationFilter_ variable has been set by the user in the configurat...
virtual bool setSensorCalibration(const calibration::SensorCalibration &sensorCalibration)=0
Sets a sensor calibration to the device. It's virtual since it's implementation-specific.
bool hasSensorCalibration() const
Checks if the value of the sensorCalibration_ variable has been set by the user in the configuration ...
Statusword statusword_
The current statusword.
std::multimap< int, DeviceDisconnectedCb, std::greater< int > > deviceDisconnectedCbs_
bool hasSaveConfiguration() const
Checks if the value of the saveConfiguration_ variable has been set by the user in the configuration ...
#define ROS_INFO_STREAM(args)
void errorCb()
Calls the callbacks in the error callbacks list.
std::multimap< int, ErrorRecoveredCb, std::greater< int > > errorRecoveredCbs_
TimePoint getStamp() const
Gets the stamp variable.
NodeHandlePtr nh_
The node handle of the ROS node, used by the publishers.
std::multimap< int, ErrorCb, std::greater< int > > errorCbs_
uint8_t getImuAngularRateRange() const
Gets the imuAngularRateRange variable.
void setStatusword(Statusword &statusword)
Sets the statusword of the device.
const calibration::SensorCalibration & getSensorCalibration() const
Gets the sensorCalibration variable.
static constexpr double NAN_VALUE
NaN abbreviation for convenience.
bool deviceIsInFatalState()
Checks if the device is in fatal state.
virtual void preSetupConfiguration()=0
Pre-setup configuration hook.
const SensorConfiguration & getSensorConfiguration() const
Gets the sensorConfiguration variable.
virtual bool setAngularRateRange(const unsigned int range)=0
Sets an angular rate range to the device. It's virtual since it's implementation-specific.
configuration::Configuration configuration_
The Configuration of the device.
bool getSaveConfiguration() const
Gets the saveConfiguration variable.
std::recursive_mutex readingMutex_
The mutex for accessing the reading.
bool hasImuAngularRateRange() const
Checks if the value of the imuAngularRateRange_ variable has been set by the user in the configuratio...
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, FatalRecoveredCb, std::greater< int > > fatalRecoveredCbs_
virtual bool saveConfigParameter()=0
Saves the current configuration to the device. It's virtual since it's implementation-specific.
bool hasImuAngularRateFilter() const
Checks if the value of the imuAngularRateFilter_ variable has been set by the user in the configurati...
void deviceReconnectedCb()
Calls the callbacks in the device reconnected callbacks list.
Class representing the different states the communication or the sensors can be in.
void clearGoalStateEnum()
Clears the goal state enumeration.
std::multimap< int, ReadingCb, std::greater< int > > readingCbs_
std::multimap< int, DeviceReconnectedCb, std::greater< int > > deviceReconnectedCbs_
virtual bool setSensorConfiguration(const configuration::SensorConfiguration &sensorConfiguration)=0
Sets a sensor configuration to the device. It's virtual since it's implementation-specific.
rokubimini
Author(s):
autogenerated on Sat Apr 15 2023 02:53:52