Public Types | Public Member Functions | Private Attributes | List of all members
WG021 Class Reference

#include <wg021.h>

Inheritance diagram for WG021:
Inheritance graph
[legend]

Public Types

enum  { PRODUCT_CODE = 6805021 }
 
enum  {
  PROJECTOR_CONFIG_ENABLE = 8, PROJECTOR_CONFIG_ENABLE_ENABLED = 8, PROJECTOR_CONFIG_ENABLE_DISABLED = 0, PROJECTOR_CONFIG_ACTION = 4,
  PROJECTOR_CONFIG_ACTION_ON = 4, PROJECTOR_CONFIG_ACTION_OFF = 0, PROJECTOR_CONFIG_POLARITY = 2, PROJECTOR_CONFIG_POLARITY_ACTIVE_HIGH = 2,
  PROJECTOR_CONFIG_POLARITY_ACTIVE_LOW = 0, PROJECTOR_CONFIG_STATE = 1, PROJECTOR_CONFIG_STATE_HIGH = 1, PROJECTOR_CONFIG_STATE_LOW = 0
}
 
- Public Types inherited from EthercatDevice
enum  AddrMode { FIXED_ADDR =0, POSITIONAL_ADDR =1 }
 

Public Member Functions

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...
 
int initialize (pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true)
 
void packCommand (unsigned char *buffer, bool halt, bool reset)
 
bool unpackState (unsigned char *this_buffer, unsigned char *prev_buffer)
 
 WG021 ()
 
- Public Member Functions inherited from WG0X
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 ()
 
- Public Member Functions inherited from EthercatDevice
virtual void construct (ros::NodeHandle &nh)
 
 EthercatDevice ()
 
void ethercatDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned numPorts)
 Adds diagnostic information for EtherCAT ports. More...
 
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...
 
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 ()
 

Private Attributes

pr2_hardware_interface::DigitalOut digital_out_A_
 
pr2_hardware_interface::DigitalOut digital_out_B_
 
pr2_hardware_interface::DigitalOut digital_out_I_
 
pr2_hardware_interface::DigitalOut digital_out_L0_
 
pr2_hardware_interface::DigitalOut digital_out_L1_
 
pr2_hardware_interface::DigitalOut digital_out_M_
 
pr2_hardware_interface::Projector projector_
 

Additional Inherited Members

- Static Public Member Functions inherited from WG0X
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 Public Member Functions inherited from EthercatDevice
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...
 
- Public Attributes inherited from EthercatDevice
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_
 
- Protected Types inherited from WG0X
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...
 
- Protected Member Functions inherited from WG0X
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 Protected Member Functions inherited from WG0X
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)
 
- Protected Attributes inherited from WG0X
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::MotorHeatingModelmotor_heating_model_
 
MotorModelmotor_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 Protected Attributes inherited from WG0X
static const unsigned ACTUATOR_INFO_PAGE = 4095
 
static const unsigned COMMAND_PHY_ADDR = 0x1000
 
static boost::shared_ptr< ethercat_hardware::MotorHeatingModelCommonmotor_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
 

Detailed Description

Definition at line 85 of file wg021.h.

Member Enumeration Documentation

anonymous enum
Enumerator
PRODUCT_CODE 

Definition at line 94 of file wg021.h.

anonymous enum
Enumerator
PROJECTOR_CONFIG_ENABLE 
PROJECTOR_CONFIG_ENABLE_ENABLED 
PROJECTOR_CONFIG_ENABLE_DISABLED 
PROJECTOR_CONFIG_ACTION 
PROJECTOR_CONFIG_ACTION_ON 
PROJECTOR_CONFIG_ACTION_OFF 
PROJECTOR_CONFIG_POLARITY 
PROJECTOR_CONFIG_POLARITY_ACTIVE_HIGH 
PROJECTOR_CONFIG_POLARITY_ACTIVE_LOW 
PROJECTOR_CONFIG_STATE 
PROJECTOR_CONFIG_STATE_HIGH 
PROJECTOR_CONFIG_STATE_LOW 

Definition at line 98 of file wg021.h.

Constructor & Destructor Documentation

WG021::WG021 ( )
inline

Definition at line 88 of file wg021.h.

Member Function Documentation

void WG021::construct ( EtherCAT_SlaveHandler *  sh,
int &  start_address 
)
virtual

< Construct EtherCAT device

Construct non-EtherCAT device

Reimplemented from EthercatDevice.

Definition at line 54 of file wg021.cpp.

void WG021::diagnostics ( diagnostic_updater::DiagnosticStatusWrapper d,
unsigned char *  buffer 
)
virtual

For EtherCAT device that only publish one EtherCAT Status message. If sub-class implements multiDiagnostics() then diagnostics() is not used.

Parameters
dDiagnostics status wrapper.
bufferPointer to slave process data.

Reimplemented from EthercatDevice.

Definition at line 243 of file wg021.cpp.

int WG021::initialize ( pr2_hardware_interface::HardwareInterface hw,
bool  allow_unprogrammed = true 
)
virtual

Reimplemented from WG0X.

Definition at line 115 of file wg021.cpp.

void WG021::packCommand ( unsigned char *  buffer,
bool  halt,
bool  reset 
)
virtual
Parameters
resetwhen asserted this will clear diagnostic error conditions device safety disable
haltwhile asserted will disable actuator, usually by disabling H-bridge

Reimplemented from EthercatDevice.

Definition at line 160 of file wg021.cpp.

bool WG021::unpackState ( unsigned char *  this_buffer,
unsigned char *  prev_buffer 
)
virtual

Reimplemented from EthercatDevice.

Definition at line 189 of file wg021.cpp.

Member Data Documentation

pr2_hardware_interface::DigitalOut WG021::digital_out_A_
private

Definition at line 117 of file wg021.h.

pr2_hardware_interface::DigitalOut WG021::digital_out_B_
private

Definition at line 118 of file wg021.h.

pr2_hardware_interface::DigitalOut WG021::digital_out_I_
private

Definition at line 119 of file wg021.h.

pr2_hardware_interface::DigitalOut WG021::digital_out_L0_
private

Definition at line 121 of file wg021.h.

pr2_hardware_interface::DigitalOut WG021::digital_out_L1_
private

Definition at line 122 of file wg021.h.

pr2_hardware_interface::DigitalOut WG021::digital_out_M_
private

Definition at line 120 of file wg021.h.

pr2_hardware_interface::Projector WG021::projector_
private

Definition at line 123 of file wg021.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