#include <wg06.h>
Definition at line 86 of file wg06.h.
◆ FTParamsInternal()
FTParamsInternal::FTParamsInternal |
( |
| ) |
|
◆ calibration_coeff() [1/2]
const double& FTParamsInternal::calibration_coeff |
( |
unsigned |
row, |
|
|
unsigned |
col |
|
) |
| const |
|
inline |
◆ calibration_coeff() [2/2]
double& FTParamsInternal::calibration_coeff |
( |
unsigned |
row, |
|
|
unsigned |
col |
|
) |
| |
|
inline |
◆ gain() [1/2]
const double& FTParamsInternal::gain |
( |
unsigned |
ch_num | ) |
const |
|
inline |
◆ gain() [2/2]
double& FTParamsInternal::gain |
( |
unsigned |
ch_num | ) |
|
|
inline |
◆ getDoubleArray()
bool FTParamsInternal::getDoubleArray |
( |
XmlRpc::XmlRpcValue |
params, |
|
|
const char * |
name, |
|
|
double * |
results, |
|
|
unsigned |
len |
|
) |
| |
◆ getRosParams()
Grabs ft rosparams from a given node hande namespace.
The force/torque parameters consist of 6x ADC offset values 6x6 gain matrix as 6-elment array of 6-element arrays of doubles
- Returns
- True, if there are no problems.
Definition at line 1158 of file wg06.cpp.
◆ offset() [1/2]
const double& FTParamsInternal::offset |
( |
unsigned |
ch_num | ) |
const |
|
inline |
◆ offset() [2/2]
double& FTParamsInternal::offset |
( |
unsigned |
ch_num | ) |
|
|
inline |
◆ print()
void FTParamsInternal::print |
( |
| ) |
const |
◆ calibration_coeff_
double FTParamsInternal::calibration_coeff_[36] |
◆ gains_
double FTParamsInternal::gains_[6] |
◆ offsets_
double FTParamsInternal::offsets_[6] |
The documentation for this class was generated from the following files: