|
void | construct (EtherCAT_SlaveHandler *sh, int &start_address) |
| < Construct EtherCAT device More...
|
|
int | initialize (pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true) |
|
virtual void | multiDiagnostics (vector< diagnostic_msgs::DiagnosticStatus > &vec, unsigned char *buffer) |
| For EtherCAT devices that publish more than one EtherCAT Status message. If sub-class implements multiDiagnostics() then diagnostics() is not used. More...
|
|
void | packCommand (unsigned char *buffer, bool halt, bool reset) |
|
bool | unpackState (unsigned char *this_buffer, unsigned char *prev_buffer) |
|
| WG06 () |
|
| ~WG06 () |
|
virtual void | collectDiagnostics (EthercatCom *com) |
|
void | construct (EtherCAT_SlaveHandler *sh, int &start_address) |
| < Construct EtherCAT device More...
|
|
void | diagnostics (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *) |
| For EtherCAT device that only publish one EtherCAT Status message. If sub-class implements multiDiagnostics() then diagnostics() is not used. More...
|
|
void | packCommand (unsigned char *buffer, bool halt, bool reset) |
|
bool | program (EthercatCom *com, const WG0XActuatorInfo &actutor_info) |
| Programs acutator and heating parameters into device EEPROM. More...
|
|
bool | program (EthercatCom *com, const MotorHeatingModelParametersEepromConfig &heating_config) |
| Programs motor heating parameters into device EEPROM. More...
|
|
bool | publishTrace (const string &reason, unsigned level, unsigned delay) |
| Asks device to publish (motor) trace. Only works for devices that support it. More...
|
|
bool | readActuatorInfoFromEeprom (EthercatCom *com, WG0XActuatorInfo &actuator_info) |
| Reads actuator info from eeprom. More...
|
|
bool | readMotorHeatingModelParametersFromEeprom (EthercatCom *com, MotorHeatingModelParametersEepromConfig &config) |
| Reads actuator info from eeprom. More...
|
|
bool | unpackState (unsigned char *this_buffer, unsigned char *prev_buffer) |
|
| WG0X () |
|
virtual | ~WG0X () |
|
virtual void | construct (ros::NodeHandle &nh) |
|
| EthercatDevice () |
|
void | ethercatDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned numPorts) |
| Adds diagnostic information for EtherCAT ports. More...
|
|
int | readData (EthercatCom *com, EC_UINT address, void *buffer, EC_UINT length, AddrMode addrMode) |
|
int | readWriteData (EthercatCom *com, EC_UINT address, void *buffer, EC_UINT length, AddrMode addrMode) |
|
int | writeData (EthercatCom *com, EC_UINT address, void const *buffer, EC_UINT length, AddrMode addrMode) |
|
virtual | ~EthercatDevice () |
|
|
static double | calcEncoderVelocity (int32_t new_position, uint32_t new_timestamp, int32_t old_position, uint32_t old_timestamp) |
|
static double | convertRawTemperature (int16_t raw_temp) |
| Converts raw 16bit temperature value returned by device into value in degress Celcius. More...
|
|
static int32_t | positionDiff (int32_t new_position, int32_t old_position) |
|
static ros::Duration | timediffToDuration (int32_t timediff_usec) |
|
static int32_t | timestampDiff (uint32_t new_timestamp, uint32_t old_timestamp) |
|
static int | readData (EthercatCom *com, EtherCAT_SlaveHandler *sh, EC_UINT address, void *buffer, EC_UINT length, AddrMode addrMode) |
| Read data from device ESC. More...
|
|
static int | readWriteData (EthercatCom *com, EtherCAT_SlaveHandler *sh, EC_UINT address, void *buffer, EC_UINT length, AddrMode addrMode) |
| Read then write data to ESC. More...
|
|
static int | writeData (EthercatCom *com, EtherCAT_SlaveHandler *sh, EC_UINT address, void const *buffer, EC_UINT length, AddrMode addrMode) |
| Write data to device ESC. More...
|
|
enum EthercatDevice::AddrMode | __attribute__ |
|
unsigned int | command_size_ |
|
EthercatDeviceDiagnostics | deviceDiagnostics [2] |
|
diagnostic_updater::DiagnosticStatusWrapper | diagnostic_status_ |
|
pthread_mutex_t | diagnosticsLock_ |
|
unsigned | newDiagnosticsIndex_ |
|
pthread_mutex_t | newDiagnosticsIndexLock_ |
|
EtherCAT_SlaveHandler * | sh_ |
|
unsigned int | status_size_ |
|
bool | use_ros_ |
|
enum | {
MODE_OFF = 0x00,
MODE_ENABLE = (1 << 0),
MODE_CURRENT = (1 << 1),
MODE_SAFETY_RESET = (1 << 4),
MODE_SAFETY_LOCKOUT = (1 << 5),
MODE_UNDERVOLTAGE = (1 << 6),
MODE_RESET = (1 << 7)
} |
|
enum | { WG05_PRODUCT_CODE = 6805005,
WG06_PRODUCT_CODE = 6805006,
WG021_PRODUCT_CODE = 6805021
} |
|
enum | { NO_CALIBRATION =0,
CONTROLLER_CALIBRATION =1,
SAVED_CALIBRATION =2
} |
|
enum | { LIMIT_SENSOR_0_STATE = (1 << 0),
LIMIT_SENSOR_1_STATE = (1 << 1),
LIMIT_ON_TO_OFF = (1 << 2),
LIMIT_OFF_TO_ON = (1 << 3)
} |
|
enum | {
SAFETY_DISABLED = (1 << 0),
SAFETY_UNDERVOLTAGE = (1 << 1),
SAFETY_OVER_CURRENT = (1 << 2),
SAFETY_BOARD_OVER_TEMP = (1 << 3),
SAFETY_HBRIDGE_OVER_TEMP = (1 << 4),
SAFETY_OPERATIONAL = (1 << 5),
SAFETY_WATCHDOG = (1 << 6)
} |
|
enum | AppRamStatus { APP_RAM_PRESENT =1,
APP_RAM_MISSING =2,
APP_RAM_NOT_APPLICABLE =3
} |
| Different possible states for application ram on device. More...
|
|
void | clearErrorFlags (void) |
|
bool | initializeMotorHeatingModel (bool allow_unprogrammed) |
|
bool | initializeMotorModel (pr2_hardware_interface::HardwareInterface *hw, const string &device_description, double max_pwm_ratio, double board_resistance, bool poor_measured_motor_voltage) |
| Allocates and initialized motor trace for WG0X devices than use it (WG006, WG005) More...
|
|
bool | lockWG0XDiagnostics () |
|
void | publishGeneralDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &d) |
|
void | publishMailboxDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &d) |
|
bool | readAppRam (EthercatCom *com, double &zero_offset) |
|
int | readMailbox (EthercatCom *com, unsigned address, void *data, unsigned length) |
| Read data from WG0X local bus using mailbox communication. More...
|
|
bool | tryLockWG0XDiagnostics () |
|
void | unlockWG0XDiagnostics () |
|
bool | verifyChecksum (const void *buffer, unsigned size) |
|
bool | verifyState (WG0XStatus *this_status, WG0XStatus *prev_status) |
|
bool | writeAppRam (EthercatCom *com, double zero_offset) |
|
int | writeMailbox (EthercatCom *com, unsigned address, void const *data, unsigned length) |
| Write data to WG0X local bus using mailbox communication. More...
|
|
static void | copyActuatorInfo (ethercat_hardware::ActuatorInfo &out, const WG0XActuatorInfo &in) |
| Fills in ethercat_hardware::ActuatorInfo from WG0XActuatorInfo. More...
|
|
static string | modeString (uint8_t mode) |
|
static string | safetyDisableString (uint8_t status) |
|
static bool | timestamp_jump (uint32_t timestamp, uint32_t last_timestamp, uint32_t amount) |
|
enum WG0X:: { ... } | __attribute__ |
|
pr2_hardware_interface::Actuator | actuator_ |
|
WG0XActuatorInfo | actuator_info_ |
|
ethercat_hardware::ActuatorInfo | actuator_info_msg_ |
|
AppRamStatus | app_ram_status_ |
|
uint8_t | board_major_ |
| Printed circuit board revision (for this value 0=='A', 1=='B') More...
|
|
uint8_t | board_minor_ |
| Printed circuit assembly revision. More...
|
|
double | cached_zero_offset_ |
|
int | calibration_status_ |
|
WG0XConfigInfo | config_info_ |
|
int | consecutive_drops_ |
|
pr2_hardware_interface::DigitalOut | digital_out_ |
|
bool | disable_motor_model_checking_ |
|
int | drops_ |
|
ethercat_hardware::WGEeprom | eeprom_ |
| Access to device eeprom. More...
|
|
bool | encoder_errors_detected_ |
|
bool | fpga_internal_reset_detected_ |
|
uint8_t | fw_major_ |
|
uint8_t | fw_minor_ |
|
bool | has_error_ |
|
bool | in_lockout_ |
|
uint32_t | last_last_timestamp_ |
|
uint32_t | last_timestamp_ |
|
ethercat_hardware::WGMailbox | mailbox_ |
| Mailbox access to device. More...
|
|
uint16_t | max_board_temperature_ |
|
uint16_t | max_bridge_temperature_ |
|
int | max_consecutive_drops_ |
|
double | max_current_ |
| min(board current limit, actuator current limit) More...
|
|
boost::shared_ptr< ethercat_hardware::MotorHeatingModel > | motor_heating_model_ |
|
MotorModel * | motor_model_ |
|
ethercat_hardware::MotorTraceSample | motor_trace_sample_ |
|
pr2_hardware_interface::DigitalOut | publish_motor_trace_ |
|
bool | resetting_ |
|
ros::Duration | sample_timestamp_ |
|
bool | status_checksum_error_ |
|
bool | timestamp_jump_detected_ |
|
bool | too_many_dropped_packets_ |
|
WG0XDiagnostics | wg0x_collect_diagnostics_ |
|
pthread_mutex_t | wg0x_diagnostics_lock_ |
|
WG0XDiagnostics | wg0x_publish_diagnostics_ |
|
static const unsigned | ACTUATOR_INFO_PAGE = 4095 |
|
static const unsigned | COMMAND_PHY_ADDR = 0x1000 |
|
static boost::shared_ptr< ethercat_hardware::MotorHeatingModelCommon > | motor_heating_model_common_ |
|
static const unsigned | PDO_COMMAND_SYNCMAN_NUM = 0 |
|
static const unsigned | PDO_STATUS_SYNCMAN_NUM = 1 |
|
static const int | PWM_MAX = 0x4000 |
|
static const unsigned | STATUS_PHY_ADDR = 0x2000 |
|
Definition at line 163 of file wg06.h.
void WG06::convertFTDataSampleToWrench |
( |
const FTDataSample & |
sample, |
|
|
geometry_msgs::Wrench & |
wrench |
|
) |
| |
|
private |
Convert FTDataSample to Wrench using gain, offset, and coefficient matrix.
perform offset and gains multiplication on raw data and then multiply by calibration matrix to get force and torque values. The calibration matrix is based on "raw" deltaR/R values from strain gauges
Force/Torque = Coeff * ADCVoltage
Coeff = RawCoeff / ( ExcitationVoltage * AmplifierGain ) = RawCoeff / ( 2.5V * AmplifierGain )
ADCVoltage = Vref / 2^16 = 2.5 / 2^16
Force/Torque = RawCalibrationCoeff / ( ExcitationVoltage * AmplifierGain ) * (ADCValues * 2.5V/2^16) = (RawCalibration * ADCValues) / (AmplifierGain * 2^16)
Note on hardware circuit and Vref and excitation voltage should have save value. Thus, with Force/Torque calculation they cancel out.
Definition at line 646 of file wg06.cpp.