Public Member Functions | Public Attributes | List of all members
FTParamsInternal Class Reference

#include <wg06.h>

Public Member Functions

const double & calibration_coeff (unsigned row, unsigned col) const
 
double & calibration_coeff (unsigned row, unsigned col)
 
 FTParamsInternal ()
 
const double & gain (unsigned ch_num) const
 
double & gain (unsigned ch_num)
 
bool getDoubleArray (XmlRpc::XmlRpcValue params, const char *name, double *results, unsigned len)
 
bool getRosParams (ros::NodeHandle nh)
 Grabs ft rosparams from a given node hande namespace. More...
 
const double & offset (unsigned ch_num) const
 
double & offset (unsigned ch_num)
 
void print () const
 

Public Attributes

double calibration_coeff_ [36]
 
double gains_ [6]
 
double offsets_ [6]
 

Detailed Description

Definition at line 86 of file wg06.h.

Constructor & Destructor Documentation

FTParamsInternal::FTParamsInternal ( )

Definition at line 1077 of file wg06.cpp.

Member Function Documentation

const double& FTParamsInternal::calibration_coeff ( unsigned  row,
unsigned  col 
) const
inline

Definition at line 91 of file wg06.h.

double& FTParamsInternal::calibration_coeff ( unsigned  row,
unsigned  col 
)
inline

Definition at line 92 of file wg06.h.

const double& FTParamsInternal::gain ( unsigned  ch_num) const
inline

Definition at line 97 of file wg06.h.

double& FTParamsInternal::gain ( unsigned  ch_num)
inline

Definition at line 98 of file wg06.h.

bool FTParamsInternal::getDoubleArray ( XmlRpc::XmlRpcValue  params,
const char *  name,
double *  results,
unsigned  len 
)

Definition at line 1115 of file wg06.cpp.

bool FTParamsInternal::getRosParams ( ros::NodeHandle  nh)

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.

const double& FTParamsInternal::offset ( unsigned  ch_num) const
inline

Definition at line 94 of file wg06.h.

double& FTParamsInternal::offset ( unsigned  ch_num)
inline

Definition at line 95 of file wg06.h.

void FTParamsInternal::print ( ) const

Definition at line 1094 of file wg06.cpp.

Member Data Documentation

double FTParamsInternal::calibration_coeff_[36]

Definition at line 104 of file wg06.h.

double FTParamsInternal::gains_[6]

Definition at line 106 of file wg06.h.

double FTParamsInternal::offsets_[6]

Definition at line 105 of file wg06.h.


The documentation for this class was generated from the following files:


ethercat_hardware
Author(s): Rob Wheeler , Derek King
autogenerated on Fri Mar 15 2019 02:53:29