Class holding the configuration of the sensor. More...
#include <Configuration.hpp>
Public Types | |
| using | NodeHandlePtr = std::shared_ptr< ros::NodeHandle > |
Public Member Functions | |
| Configuration ()=default | |
| Default constructor. More... | |
| Configuration (const Configuration &other) | |
| Copy constructor. More... | |
| const ForceTorqueFilter & | getForceTorqueFilter () const |
| Gets the forceTorqueFilter variable. More... | |
| const Eigen::Matrix< double, 6, 1 > & | getForceTorqueOffset () const |
| Gets the forceTorqueOffset variable. More... | |
| unsigned int | getImuAccelerationFilter () const |
| uint8_t | getImuAccelerationRange () const |
| Gets the imuAccelerationRange variable. More... | |
| unsigned int | getImuAngularRateFilter () const |
| Gets the imuAccelerationFilter variable. More... | |
| uint8_t | getImuAngularRateRange () const |
| Gets the imuAngularRateRange variable. More... | |
| bool | getSaveConfiguration () const |
| Gets the saveConfiguration variable. More... | |
| const calibration::SensorCalibration & | getSensorCalibration () const |
| Gets the sensorCalibration variable. More... | |
| const SensorConfiguration & | getSensorConfiguration () const |
| Gets the sensorConfiguration variable. More... | |
| bool | getSetReadingToNanOnDisconnect () const |
| Gets the setReadingToNanOnDisconnect variable. More... | |
| bool | getUseCustomCalibration () const |
| Gets the useCustomCalibration variable. More... | |
| bool | hasForceTorqueFilter () const |
| Checks if the value of the forceTorqueFilter_ variable has been set by the user in the configuration file. More... | |
| bool | hasForceTorqueOffset () const |
| Checks if the value of the forceTorqueOffset_ variable has been set by the user in the configuration file. More... | |
| bool | hasImuAccelerationFilter () const |
| Checks if the value of the imuAccelerationFilter_ variable has been set by the user in the configuration file. More... | |
| bool | hasImuAccelerationRange () const |
| Checks if the value of the imuAccelerationRange_ variable has been set by the user in the configuration file. More... | |
| bool | hasImuAngularRateFilter () const |
| Checks if the value of the imuAngularRateFilter_ variable has been set by the user in the configuration file. More... | |
| bool | hasImuAngularRateRange () const |
| Checks if the value of the imuAngularRateRange_ variable has been set by the user in the configuration file. More... | |
| bool | hasSaveConfiguration () const |
| Checks if the value of the saveConfiguration_ variable has been set by the user in the configuration file. More... | |
| bool | hasSensorCalibration () const |
| Checks if the value of the sensorCalibration_ variable has been set by the user in the configuration file. More... | |
| bool | hasSensorConfiguration () const |
| Checks if the value of the sensorConfiguration_ variable has been set by the user in the configuration file. More... | |
| bool | hasSetReadingToNanOnDisconnect () const |
| Checks if the value of the setReadingToNanOnDisconnect_ variable has been set by the user in the configuration file. More... | |
| bool | hasUseCustomCalibration () const |
| Checks if the value of the useCustomCalibration_ variable has been set by the user in the configuration file. More... | |
| void | load (const std::string &key, NodeHandlePtr nh) |
| Loads the configuration from the parameter server. More... | |
| Configuration & | operator= (const Configuration &other) |
| Assignment operator for Configuration. More... | |
| void | printConfiguration () const |
| Prints the existing Configuration. More... | |
| void | setForceTorqueFilter (const ForceTorqueFilter &forceTorqueFilter) |
| Sets the forceTorqueFilter variable. More... | |
| void | setForceTorqueOffset (const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset) |
| Sets the forceTorqueOffset variable. More... | |
| void | setImuAccelerationFilter (const unsigned int imuAccelerationFilter) |
| Sets the imuAccelerationFilter variable. More... | |
| void | setImuAccelerationRange (const uint8_t imuAccelerationRange) |
| Sets the imuAccelerationRange variable. More... | |
| void | setImuAngularRateFilter (const unsigned int imuAngularRateFilter) |
| Sets the imuAngularRateFilter variable. More... | |
| void | setImuAngularRateRange (const uint8_t imuAngularRateRange) |
| Sets the imuAngularRateRange variable. More... | |
| void | setSaveConfiguration (const bool saveConfiguration) |
| Sets the saveConfiguration variable. More... | |
| void | setSensorCalibration (const calibration::SensorCalibration &sensorCalibration) |
| Sets the sensorCalibration variable. More... | |
| void | setSensorConfiguration (const SensorConfiguration &sensorConfiguration) |
| Sets the sensorConfiguration variable. More... | |
| void | setSetReadingToNanOnDisconnect (const bool setReadingToNanOnDisconnect) |
| Sets the setReadingToNanOnDisconnect variable. More... | |
| void | setUseCustomCalibration (const bool useCustomCalibration) |
| Sets the useCustomCalibration variable. More... | |
| virtual | ~Configuration ()=default |
Protected Attributes | |
| ForceTorqueFilter | forceTorqueFilter_ |
| The forceTorqueFilter variable. More... | |
| Eigen::Matrix< double, 6, 1 > | forceTorqueOffset_ |
| The forceTorqueOffset variable. More... | |
| bool | hasForceTorqueFilter_ |
| Flag indicating if forceTorqueFilter_ is set. More... | |
| bool | hasForceTorqueOffset_ |
| Flag indicating if forceTorqueOffset_ is set. More... | |
| bool | hasImuAccelerationFilter_ |
| Flag indicating if imuAccelerationFilter_ is set. More... | |
| bool | hasImuAccelerationRange_ |
| Flag indicating if imuAccelerationRange_ is set. More... | |
| bool | hasImuAngularRateFilter_ |
| Flag indicating if imuAngularRateFilter_ is set. More... | |
| bool | hasImuAngularRateRange_ |
| Flag indicating if imuAngularRateRange_ is set. More... | |
| bool | hasSaveConfiguration_ |
| Flag indicating if saveConfiguration_ is set. More... | |
| bool | hasSensorCalibration_ |
| Flag indicating if sensorCalibration_ is set. More... | |
| bool | hasSensorConfiguration_ |
| Flag indicating if sensorConfiguration_ is set. More... | |
| bool | hasSetReadingToNanOnDisconnect_ |
| Flag indicating if setReadingToNanOnDisconnect_ is set. More... | |
| bool | hasUseCustomCalibration_ |
| Flag indicating if useCustomCalibration_ is set. More... | |
| unsigned int | imuAccelerationFilter_ |
| The imuAccelerationFilter variable. More... | |
| unsigned int | imuAccelerationRange_ |
| The imuAccelerationRange variable. More... | |
| unsigned int | imuAngularRateFilter_ |
| The imuAngularRateFilter variable. More... | |
| unsigned int | imuAngularRateRange_ |
| The imuAngularRateRange variable. More... | |
| std::recursive_mutex | mutex_ |
| Mutex for synchronized access on the object's private variables. More... | |
| bool | saveConfiguration_ |
| The saveConfiguration_ variable. More... | |
| calibration::SensorCalibration | sensorCalibration_ |
| The sensorCalibration variable. More... | |
| SensorConfiguration | sensorConfiguration_ |
| The sensorConfiguration variable. More... | |
| bool | setReadingToNanOnDisconnect_ |
| The setReadingToNanOnDisconnect variable. More... | |
| bool | useCustomCalibration_ |
| The useCustomCalibration variable. More... | |
Class holding the configuration of the sensor.
Definition at line 24 of file Configuration.hpp.
| using rokubimini::configuration::Configuration::NodeHandlePtr = std::shared_ptr<ros::NodeHandle> |
Definition at line 27 of file Configuration.hpp.
|
default |
Default constructor.
| rokubimini::configuration::Configuration::Configuration | ( | const Configuration & | other | ) |
Copy constructor.
| other | The other configuration to copy from. |
|
virtualdefault |
| const ForceTorqueFilter & rokubimini::configuration::Configuration::getForceTorqueFilter | ( | ) | const |
Gets the forceTorqueFilter variable.
Definition at line 249 of file Configuration.cpp.
| const Eigen::Matrix< double, 6, 1 > & rokubimini::configuration::Configuration::getForceTorqueOffset | ( | ) | const |
Gets the forceTorqueOffset variable.
Definition at line 261 of file Configuration.cpp.
| unsigned int rokubimini::configuration::Configuration::getImuAccelerationFilter | ( | ) | const |
Definition at line 333 of file Configuration.cpp.
| uint8_t rokubimini::configuration::Configuration::getImuAccelerationRange | ( | ) | const |
Gets the imuAccelerationRange variable.
Definition at line 357 of file Configuration.cpp.
| unsigned int rokubimini::configuration::Configuration::getImuAngularRateFilter | ( | ) | const |
Gets the imuAccelerationFilter variable.
Gets the imuAngularRateFilter variable.
Definition at line 345 of file Configuration.cpp.
| uint8_t rokubimini::configuration::Configuration::getImuAngularRateRange | ( | ) | const |
Gets the imuAngularRateRange variable.
Definition at line 369 of file Configuration.cpp.
| bool rokubimini::configuration::Configuration::getSaveConfiguration | ( | ) | const |
Gets the saveConfiguration variable.
Definition at line 285 of file Configuration.cpp.
| const calibration::SensorCalibration & rokubimini::configuration::Configuration::getSensorCalibration | ( | ) | const |
Gets the sensorCalibration variable.
Definition at line 321 of file Configuration.cpp.
| const SensorConfiguration & rokubimini::configuration::Configuration::getSensorConfiguration | ( | ) | const |
Gets the sensorConfiguration variable.
Definition at line 309 of file Configuration.cpp.
| bool rokubimini::configuration::Configuration::getSetReadingToNanOnDisconnect | ( | ) | const |
Gets the setReadingToNanOnDisconnect variable.
Definition at line 297 of file Configuration.cpp.
| bool rokubimini::configuration::Configuration::getUseCustomCalibration | ( | ) | const |
Gets the useCustomCalibration variable.
Definition at line 273 of file Configuration.cpp.
| bool rokubimini::configuration::Configuration::hasForceTorqueFilter | ( | ) | const |
Checks if the value of the forceTorqueFilter_ variable has been set by the user in the configuration file.
Definition at line 393 of file Configuration.cpp.
| bool rokubimini::configuration::Configuration::hasForceTorqueOffset | ( | ) | const |
Checks if the value of the forceTorqueOffset_ variable has been set by the user in the configuration file.
Definition at line 399 of file Configuration.cpp.
| bool rokubimini::configuration::Configuration::hasImuAccelerationFilter | ( | ) | const |
Checks if the value of the imuAccelerationFilter_ variable has been set by the user in the configuration file.
Definition at line 429 of file Configuration.cpp.
| bool rokubimini::configuration::Configuration::hasImuAccelerationRange | ( | ) | const |
Checks if the value of the imuAccelerationRange_ variable has been set by the user in the configuration file.
Definition at line 423 of file Configuration.cpp.
| bool rokubimini::configuration::Configuration::hasImuAngularRateFilter | ( | ) | const |
Checks if the value of the imuAngularRateFilter_ variable has been set by the user in the configuration file.
Definition at line 435 of file Configuration.cpp.
| bool rokubimini::configuration::Configuration::hasImuAngularRateRange | ( | ) | const |
Checks if the value of the imuAngularRateRange_ variable has been set by the user in the configuration file.
Definition at line 375 of file Configuration.cpp.
| bool rokubimini::configuration::Configuration::hasSaveConfiguration | ( | ) | const |
Checks if the value of the saveConfiguration_ variable has been set by the user in the configuration file.
Definition at line 411 of file Configuration.cpp.
| bool rokubimini::configuration::Configuration::hasSensorCalibration | ( | ) | const |
Checks if the value of the sensorCalibration_ variable has been set by the user in the configuration file.
Definition at line 417 of file Configuration.cpp.
| bool rokubimini::configuration::Configuration::hasSensorConfiguration | ( | ) | const |
Checks if the value of the sensorConfiguration_ variable has been set by the user in the configuration file.
Definition at line 387 of file Configuration.cpp.
| bool rokubimini::configuration::Configuration::hasSetReadingToNanOnDisconnect | ( | ) | const |
Checks if the value of the setReadingToNanOnDisconnect_ variable has been set by the user in the configuration file.
Definition at line 381 of file Configuration.cpp.
| bool rokubimini::configuration::Configuration::hasUseCustomCalibration | ( | ) | const |
Checks if the value of the useCustomCalibration_ variable has been set by the user in the configuration file.
Definition at line 405 of file Configuration.cpp.
| void rokubimini::configuration::Configuration::load | ( | const std::string & | key, |
| NodeHandlePtr | nh | ||
| ) |
Loads the configuration from the parameter server.
| key | The key to search in the parameter server. |
| nh | The ROS NodeHandle to access the parameter server. |
Definition at line 7 of file Configuration.cpp.
| Configuration & rokubimini::configuration::Configuration::operator= | ( | const Configuration & | other | ) |
Assignment operator for Configuration.
Definition at line 216 of file Configuration.cpp.
| void rokubimini::configuration::Configuration::printConfiguration | ( | ) | const |
Prints the existing Configuration.
Definition at line 202 of file Configuration.cpp.
| void rokubimini::configuration::Configuration::setForceTorqueFilter | ( | const ForceTorqueFilter & | forceTorqueFilter | ) |
Sets the forceTorqueFilter variable.
| forceTorqueFilter | The value to set. |
Definition at line 243 of file Configuration.cpp.
| void rokubimini::configuration::Configuration::setForceTorqueOffset | ( | const Eigen::Matrix< double, 6, 1 > & | forceTorqueOffset | ) |
Sets the forceTorqueOffset variable.
| forceTorqueOffset | The value to set. |
Definition at line 255 of file Configuration.cpp.
| void rokubimini::configuration::Configuration::setImuAccelerationFilter | ( | const unsigned int | imuAccelerationFilter | ) |
Sets the imuAccelerationFilter variable.
| imuAccelerationFilter | The value to set. |
Definition at line 327 of file Configuration.cpp.
| void rokubimini::configuration::Configuration::setImuAccelerationRange | ( | const uint8_t | imuAccelerationRange | ) |
Sets the imuAccelerationRange variable.
| imuAccelerationRange | The value to set. |
Definition at line 351 of file Configuration.cpp.
| void rokubimini::configuration::Configuration::setImuAngularRateFilter | ( | const unsigned int | imuAngularRateFilter | ) |
Sets the imuAngularRateFilter variable.
| imuAngularRateFilter | The value to set. |
Definition at line 339 of file Configuration.cpp.
| void rokubimini::configuration::Configuration::setImuAngularRateRange | ( | const uint8_t | imuAngularRateRange | ) |
Sets the imuAngularRateRange variable.
| imuAngularRateRange | The value to set. |
Definition at line 363 of file Configuration.cpp.
| void rokubimini::configuration::Configuration::setSaveConfiguration | ( | const bool | saveConfiguration | ) |
Sets the saveConfiguration variable.
| saveConfiguration | The value to set. |
Definition at line 279 of file Configuration.cpp.
| void rokubimini::configuration::Configuration::setSensorCalibration | ( | const calibration::SensorCalibration & | sensorCalibration | ) |
Sets the sensorCalibration variable.
| sensorCalibration | The value to set. |
Definition at line 315 of file Configuration.cpp.
| void rokubimini::configuration::Configuration::setSensorConfiguration | ( | const SensorConfiguration & | sensorConfiguration | ) |
Sets the sensorConfiguration variable.
| sensorConfiguration | The value to set. |
Definition at line 303 of file Configuration.cpp.
| void rokubimini::configuration::Configuration::setSetReadingToNanOnDisconnect | ( | const bool | setReadingToNanOnDisconnect | ) |
Sets the setReadingToNanOnDisconnect variable.
| setReadingToNanOnDisconnect | The value to set. |
Definition at line 291 of file Configuration.cpp.
| void rokubimini::configuration::Configuration::setUseCustomCalibration | ( | const bool | useCustomCalibration | ) |
Sets the useCustomCalibration variable.
| useCustomCalibration | The value to set. |
Definition at line 267 of file Configuration.cpp.
|
protected |
The forceTorqueFilter variable.
Definition at line 430 of file Configuration.hpp.
|
protected |
The forceTorqueOffset variable.
Definition at line 558 of file Configuration.hpp.
|
protected |
Flag indicating if forceTorqueFilter_ is set.
Definition at line 438 of file Configuration.hpp.
|
protected |
Flag indicating if forceTorqueOffset_ is set.
Definition at line 566 of file Configuration.hpp.
|
protected |
Flag indicating if imuAccelerationFilter_ is set.
Definition at line 502 of file Configuration.hpp.
|
protected |
Flag indicating if imuAccelerationRange_ is set.
Definition at line 534 of file Configuration.hpp.
|
protected |
Flag indicating if imuAngularRateFilter_ is set.
Definition at line 518 of file Configuration.hpp.
|
protected |
Flag indicating if imuAngularRateRange_ is set.
Definition at line 550 of file Configuration.hpp.
|
protected |
Flag indicating if saveConfiguration_ is set.
Definition at line 582 of file Configuration.hpp.
|
protected |
Flag indicating if sensorCalibration_ is set.
Definition at line 486 of file Configuration.hpp.
|
protected |
Flag indicating if sensorConfiguration_ is set.
Definition at line 454 of file Configuration.hpp.
|
protected |
Flag indicating if setReadingToNanOnDisconnect_ is set.
Definition at line 422 of file Configuration.hpp.
|
protected |
Flag indicating if useCustomCalibration_ is set.
Definition at line 470 of file Configuration.hpp.
|
protected |
The imuAccelerationFilter variable.
Definition at line 494 of file Configuration.hpp.
|
protected |
The imuAccelerationRange variable.
Definition at line 526 of file Configuration.hpp.
|
protected |
The imuAngularRateFilter variable.
Definition at line 510 of file Configuration.hpp.
|
protected |
The imuAngularRateRange variable.
Definition at line 542 of file Configuration.hpp.
|
mutableprotected |
Mutex for synchronized access on the object's private variables.
Definition at line 406 of file Configuration.hpp.
|
protected |
The saveConfiguration_ variable.
Definition at line 574 of file Configuration.hpp.
|
protected |
The sensorCalibration variable.
Definition at line 478 of file Configuration.hpp.
|
protected |
The sensorConfiguration variable.
Definition at line 446 of file Configuration.hpp.
|
protected |
The setReadingToNanOnDisconnect variable.
Definition at line 414 of file Configuration.hpp.
|
protected |
The useCustomCalibration variable.
Definition at line 462 of file Configuration.hpp.