Go to the documentation of this file.
5 namespace configuration
15 std::lock_guard<std::recursive_mutex> lock(
mutex_);
16 std::string key_string;
17 key_string = rokubiminiName +
"/set_reading_to_nan_on_disconnect";
18 if (nh->hasParam(key_string))
21 bool set_reading_to_nan_on_disconnect;
22 nh->getParam(key_string, set_reading_to_nan_on_disconnect);
30 key_string = rokubiminiName +
"/imu_acceleration_range";
31 if (nh->hasParam(key_string))
34 int imu_acceleration_range;
35 nh->getParam(key_string, imu_acceleration_range);
43 key_string = rokubiminiName +
"/imu_angular_rate_range";
44 if (nh->hasParam(key_string))
47 int imu_angular_rate_range;
48 nh->getParam(key_string, imu_angular_rate_range);
56 key_string = rokubiminiName +
"/force_torque_filter";
58 if (filter.
load(key_string, nh))
68 key_string = rokubiminiName +
"/imu_acceleration_filter";
69 if (nh->hasParam(key_string))
72 int imu_acceleration_filter;
73 nh->getParam(key_string, imu_acceleration_filter);
82 key_string = rokubiminiName +
"/imu_angular_rate_filter";
83 if (nh->hasParam(key_string))
86 int imu_angular_rate_filter;
87 nh->getParam(key_string, imu_angular_rate_filter);
96 key_string = rokubiminiName +
"/force_torque_offset";
97 Eigen::Matrix<double, 6, 1> offset;
99 std::string force_torque_key;
101 force_torque_key = key_string +
"/Fx";
102 if (nh->hasParam(force_torque_key))
105 nh->getParam(force_torque_key, offset(0, 0));
108 force_torque_key = key_string +
"/Fy";
109 if (nh->hasParam(force_torque_key))
111 nh->getParam(force_torque_key, offset(1, 0));
114 force_torque_key = key_string +
"/Fz";
115 if (nh->hasParam(force_torque_key))
117 nh->getParam(force_torque_key, offset(2, 0));
120 force_torque_key = key_string +
"/Tx";
121 if (nh->hasParam(force_torque_key))
123 nh->getParam(force_torque_key, offset(3, 0));
126 force_torque_key = key_string +
"/Ty";
127 if (nh->hasParam(force_torque_key))
129 nh->getParam(force_torque_key, offset(4, 0));
132 force_torque_key = key_string +
"/Tz";
133 if (nh->hasParam(force_torque_key))
135 nh->getParam(force_torque_key, offset(5, 0));
148 key_string = rokubiminiName +
"/sensor_configuration";
150 if (configuration.
load(key_string, nh))
161 key_string = rokubiminiName +
"/use_custom_calibration";
162 if (nh->hasParam(key_string))
165 bool use_custom_calibration;
166 nh->getParam(key_string, use_custom_calibration);
174 key_string = rokubiminiName +
"/sensor_calibration";
176 if (calibration.
load(key_string, nh))
186 key_string = rokubiminiName +
"/save_configuration";
187 if (nh->hasParam(key_string))
190 bool save_configuration;
191 nh->getParam(key_string, save_configuration);
245 std::lock_guard<std::recursive_mutex> lock(
mutex_);
251 std::lock_guard<std::recursive_mutex> lock(
mutex_);
257 std::lock_guard<std::recursive_mutex> lock(
mutex_);
263 std::lock_guard<std::recursive_mutex> lock(
mutex_);
269 std::lock_guard<std::recursive_mutex> lock(
mutex_);
275 std::lock_guard<std::recursive_mutex> lock(
mutex_);
281 std::lock_guard<std::recursive_mutex> lock(
mutex_);
287 std::lock_guard<std::recursive_mutex> lock(
mutex_);
293 std::lock_guard<std::recursive_mutex> lock(
mutex_);
299 std::lock_guard<std::recursive_mutex> lock(
mutex_);
305 std::lock_guard<std::recursive_mutex> lock(
mutex_);
311 std::lock_guard<std::recursive_mutex> lock(
mutex_);
317 std::lock_guard<std::recursive_mutex> lock(
mutex_);
323 std::lock_guard<std::recursive_mutex> lock(
mutex_);
329 std::lock_guard<std::recursive_mutex> lock(
mutex_);
335 std::lock_guard<std::recursive_mutex> lock(
mutex_);
341 std::lock_guard<std::recursive_mutex> lock(
mutex_);
347 std::lock_guard<std::recursive_mutex> lock(
mutex_);
353 std::lock_guard<std::recursive_mutex> lock(
mutex_);
359 std::lock_guard<std::recursive_mutex> lock(
mutex_);
365 std::lock_guard<std::recursive_mutex> lock(
mutex_);
371 std::lock_guard<std::recursive_mutex> lock(
mutex_);
377 std::lock_guard<std::recursive_mutex> lock(
mutex_);
383 std::lock_guard<std::recursive_mutex> lock(
mutex_);
389 std::lock_guard<std::recursive_mutex> lock(
mutex_);
395 std::lock_guard<std::recursive_mutex> lock(
mutex_);
401 std::lock_guard<std::recursive_mutex> lock(
mutex_);
407 std::lock_guard<std::recursive_mutex> lock(
mutex_);
413 std::lock_guard<std::recursive_mutex> lock(
mutex_);
419 std::lock_guard<std::recursive_mutex> lock(
mutex_);
425 std::lock_guard<std::recursive_mutex> lock(
mutex_);
431 std::lock_guard<std::recursive_mutex> lock(
mutex_);
437 std::lock_guard<std::recursive_mutex> lock(
mutex_);
void setUseCustomCalibration(const bool useCustomCalibration)
Sets the useCustomCalibration variable.
std::recursive_mutex mutex_
Mutex for synchronized access on the object's private variables.
bool load(const std::string &key, const NodeHandlePtr &nh)
Loads the sensor configuration from the parameter server.
unsigned int getImuAccelerationFilter() const
bool hasImuAccelerationRange() const
Checks if the value of the imuAccelerationRange_ variable has been set by the user in the configurati...
void setImuAccelerationRange(const uint8_t imuAccelerationRange)
Sets the imuAccelerationRange variable.
void print() const
Prints the existing sensor configuration settings.
bool getUseCustomCalibration() const
Gets the useCustomCalibration variable.
SensorConfiguration sensorConfiguration_
The sensorConfiguration variable.
const ForceTorqueFilter & getForceTorqueFilter() const
Gets the forceTorqueFilter variable.
void printConfiguration() const
Prints the existing Configuration.
bool hasUseCustomCalibration_
Flag indicating if useCustomCalibration_ is set.
bool hasForceTorqueOffset_
Flag indicating if forceTorqueOffset_ is set.
uint8_t getImuAccelerationRange() const
Gets the imuAccelerationRange variable.
bool hasImuAccelerationRange_
Flag indicating if imuAccelerationRange_ is set.
unsigned int imuAngularRateFilter_
The imuAngularRateFilter variable.
void print() const
Prints the existing Filter settings.
bool hasForceTorqueOffset() const
Checks if the value of the forceTorqueOffset_ variable has been set by the user in the configuration ...
void setSensorConfiguration(const SensorConfiguration &sensorConfiguration)
Sets the sensorConfiguration variable.
unsigned int getImuAngularRateFilter() const
Gets the imuAccelerationFilter variable.
bool hasImuAngularRateFilter_
Flag indicating if imuAngularRateFilter_ is set.
#define ROS_DEBUG_STREAM(args)
void load(const std::string &key, const NodeHandlePtr &nh)
Loads the configuration from the parameter server.
bool hasSensorConfiguration_
Flag indicating if sensorConfiguration_ is set.
void setImuAngularRateRange(const uint8_t imuAngularRateRange)
Sets the imuAngularRateRange variable.
bool hasImuAngularRateRange_
Flag indicating if imuAngularRateRange_ is set.
bool hasForceTorqueFilter() const
Checks if the value of the forceTorqueFilter_ variable has been set by the user in the configuration ...
bool hasSetReadingToNanOnDisconnect_
Flag indicating if setReadingToNanOnDisconnect_ is set.
bool getSetReadingToNanOnDisconnect() const
Gets the setReadingToNanOnDisconnect variable.
Class holding the force-torque filter settings.
bool hasImuAccelerationFilter_
Flag indicating if imuAccelerationFilter_ is set.
bool hasSetReadingToNanOnDisconnect() const
Checks if the value of the setReadingToNanOnDisconnect_ variable has been set by the user in the conf...
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...
bool load(const std::string &key, const NodeHandlePtr &nh)
Loads the calibrations from the parameter server.
void setSensorCalibration(const calibration::SensorCalibration &sensorCalibration)
Sets the sensorCalibration variable.
bool hasImuAccelerationFilter() const
Checks if the value of the imuAccelerationFilter_ variable has been set by the user in the configurat...
unsigned int imuAccelerationFilter_
The imuAccelerationFilter variable.
void setForceTorqueFilter(const ForceTorqueFilter &forceTorqueFilter)
Sets the forceTorqueFilter variable.
bool hasUseCustomCalibration() const
Checks if the value of the useCustomCalibration_ variable has been set by the user in the configurati...
bool hasSensorCalibration() const
Checks if the value of the sensorCalibration_ variable has been set by the user in the configuration ...
bool hasSaveConfiguration_
Flag indicating if saveConfiguration_ is set.
calibration::SensorCalibration sensorCalibration_
The sensorCalibration variable.
bool setReadingToNanOnDisconnect_
The setReadingToNanOnDisconnect variable.
bool hasSaveConfiguration() const
Checks if the value of the saveConfiguration_ variable has been set by the user in the configuration ...
bool saveConfiguration_
The saveConfiguration_ variable.
#define ROS_INFO_STREAM(args)
bool hasForceTorqueFilter_
Flag indicating if forceTorqueFilter_ is set.
unsigned int imuAngularRateRange_
The imuAngularRateRange variable.
void setSaveConfiguration(const bool saveConfiguration)
Sets the saveConfiguration variable.
void setImuAccelerationFilter(const unsigned int imuAccelerationFilter)
Sets the imuAccelerationFilter variable.
bool hasSensorCalibration_
Flag indicating if sensorCalibration_ is set.
Configuration & operator=(const Configuration &other)
Assignment operator for Configuration.
void setSetReadingToNanOnDisconnect(const bool setReadingToNanOnDisconnect)
Sets the setReadingToNanOnDisconnect variable.
unsigned int imuAccelerationRange_
The imuAccelerationRange variable.
uint8_t getImuAngularRateRange() const
Gets the imuAngularRateRange variable.
ForceTorqueFilter forceTorqueFilter_
The forceTorqueFilter variable.
bool useCustomCalibration_
The useCustomCalibration variable.
Class holding the configuration of the sensor.
const calibration::SensorCalibration & getSensorCalibration() const
Gets the sensorCalibration variable.
Class holding the sensor configuration settings.
const SensorConfiguration & getSensorConfiguration() const
Gets the sensorConfiguration variable.
The SensorCalibration class is used for holding the calibration information of each rokubi mini senso...
bool getSaveConfiguration() const
Gets the saveConfiguration variable.
bool hasImuAngularRateRange() const
Checks if the value of the imuAngularRateRange_ variable has been set by the user in the configuratio...
void setForceTorqueOffset(const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset)
Sets the forceTorqueOffset variable.
void setImuAngularRateFilter(const unsigned int imuAngularRateFilter)
Sets the imuAngularRateFilter variable.
bool hasImuAngularRateFilter() const
Checks if the value of the imuAngularRateFilter_ variable has been set by the user in the configurati...
Eigen::Matrix< double, 6, 1 > forceTorqueOffset_
The forceTorqueOffset variable.
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
bool load(const std::string &key, const NodeHandlePtr &nh)
Loads the force torque filter from the parameter server.
Configuration()=default
Default constructor.
rokubimini
Author(s):
autogenerated on Sat Apr 15 2023 02:53:52