$search

WG06 Class Reference

#include <wg06.h>

Inheritance diagram for WG06:
Inheritance graph
[legend]

List of all members.

Public Types

enum  { PRODUCT_CODE = 6805006 }

Public Member Functions

void construct (EtherCAT_SlaveHandler *sh, int &start_address)
 < Construct EtherCAT device
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.
void packCommand (unsigned char *buffer, bool halt, bool reset)
bool unpackState (unsigned char *this_buffer, unsigned char *prev_buffer)
 WG06 ()
 ~WG06 ()

Private Member Functions

void diagnosticsAccel (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer)
void diagnosticsFT (diagnostic_updater::DiagnosticStatusWrapper &d, WG06StatusWithAccelAndFT *status)
void diagnosticsWG06 (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *)
bool unpackAccel (WG06StatusWithAccel *status, WG06StatusWithAccel *last_status)
 Unpack 3-axis accelerometer samples from realtime data.
bool unpackFT (WG06StatusWithAccelAndFT *status, WG06StatusWithAccelAndFT *last_status)
 Unpack force/torque ADC samples from realtime data.
bool unpackPressure (WG06Pressure *p)
 Unpack pressure sensor samples from realtime data.

Private Attributes

realtime_tools::RealtimePublisher
< pr2_msgs::AccelerometerState > * 
accel_publisher_
pr2_hardware_interface::Accelerometer accelerometer_
unsigned accelerometer_missed_samples_
 Total of accelerometer samples that were missed.
unsigned accelerometer_samples_
 Number of accelerometer samples since last publish cycle.
uint64_t diag_last_ft_sample_count_
 F/T Sample count last time diagnostics was published.
bool first_publish_
pr2_hardware_interface::AnalogIn ft_analog_in_
uint64_t ft_missed_samples_
 Counts number of ft sensor samples that were missed.
FTParamsInternal ft_params_
realtime_tools::RealtimePublisher
< geometry_msgs::Wrench > * 
ft_publisher_
pr2_hardware_interface::AnalogIn ft_raw_analog_in_
 Provides raw F/T data to controllers.
uint64_t ft_sample_count_
 Counts number of ft sensor samples.
bool has_accel_and_ft_
 True if device has accelerometer and force/torque sensor.
uint32_t last_pressure_time_
ros::Time last_publish_time_
 Time diagnostics was last published.
bool pressure_checksum_error_
 Set true where checksum error on pressure data is detected, cleared on reset.
realtime_tools::RealtimePublisher
< pr2_msgs::PressureState > * 
pressure_publisher_
pr2_hardware_interface::PressureSensor pressure_sensors_ [2]
realtime_tools::RealtimePublisher
< ethercat_hardware::RawFTData > * 
raw_ft_publisher_
 Realtime Publisher of RAW F/T data.

Static Private Attributes

static const unsigned MAX_FT_SAMPLES = 4
static const unsigned NUM_FT_CHANNELS = 6
static const unsigned PRESSURE_PHY_ADDR = 0x2200

Detailed Description

Definition at line 151 of file wg06.h.


Member Enumeration Documentation

anonymous enum
Enumerator:
PRODUCT_CODE 

Definition at line 162 of file wg06.h.


Constructor & Destructor Documentation

WG06::WG06 (  ) 

Definition at line 52 of file wg06.cpp.

WG06::~WG06 (  ) 

Definition at line 68 of file wg06.cpp.


Member Function Documentation

void WG06::construct ( EtherCAT_SlaveHandler *  sh,
int &  start_address 
) [virtual]

< Construct EtherCAT device

Construct non-EtherCAT device

Reimplemented from WG0X.

Definition at line 74 of file wg06.cpp.

void WG06::diagnosticsAccel ( diagnostic_updater::DiagnosticStatusWrapper d,
unsigned char *  buffer 
) [private]

Definition at line 592 of file wg06.cpp.

void WG06::diagnosticsFT ( diagnostic_updater::DiagnosticStatusWrapper d,
WG06StatusWithAccelAndFT status 
) [private]

Definition at line 660 of file wg06.cpp.

void WG06::diagnosticsWG06 ( diagnostic_updater::DiagnosticStatusWrapper d,
unsigned char *  buffer 
) [private]

Definition at line 648 of file wg06.cpp.

int WG06::initialize ( pr2_hardware_interface::HardwareInterface hw,
bool  allow_unprogrammed = true 
) [virtual]

Reimplemented from WG0X.

Definition at line 178 of file wg06.cpp.

void WG06::multiDiagnostics ( vector< diagnostic_msgs::DiagnosticStatus > &  vec,
unsigned char *  buffer 
) [virtual]

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

Parameters:
vec Vector of diagnostics status messages. Slave appends one or more new diagnostic status'.
buffer Pointer to slave process data.

Reimplemented from EthercatDevice.

Definition at line 574 of file wg06.cpp.

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

Reimplemented from WG0X.

Definition at line 297 of file wg06.cpp.

bool WG06::unpackAccel ( WG06StatusWithAccel status,
WG06StatusWithAccel last_status 
) [private]

Unpack 3-axis accelerometer samples from realtime data.

Returns:
True, if there are no problems.

Definition at line 432 of file wg06.cpp.

bool WG06::unpackFT ( WG06StatusWithAccelAndFT status,
WG06StatusWithAccelAndFT last_status 
) [private]

Unpack force/torque ADC samples from realtime data.

Returns:
True, if there are no problems, false if there is something wrong with the data.

Definition at line 475 of file wg06.cpp.

bool WG06::unpackPressure ( WG06Pressure p  )  [private]

Unpack pressure sensor samples from realtime data.

Returns:
True, if there are no problems, false if there is something wrong with the data.

Definition at line 388 of file wg06.cpp.

bool WG06::unpackState ( unsigned char *  this_buffer,
unsigned char *  prev_buffer 
) [virtual]

Reimplemented from WG0X.

Definition at line 327 of file wg06.cpp.


Member Data Documentation

Definition at line 193 of file wg06.h.

Definition at line 171 of file wg06.h.

Total of accelerometer samples that were missed.

Definition at line 187 of file wg06.h.

unsigned WG06::accelerometer_samples_ [private]

Number of accelerometer samples since last publish cycle.

Definition at line 186 of file wg06.h.

F/T Sample count last time diagnostics was published.

Definition at line 199 of file wg06.h.

bool WG06::first_publish_ [private]

Definition at line 189 of file wg06.h.

Provides F/T data to controllers

Definition at line 201 of file wg06.h.

uint64_t WG06::ft_missed_samples_ [private]

Counts number of ft sensor samples that were missed.

Definition at line 198 of file wg06.h.

Definition at line 206 of file wg06.h.

Definition at line 204 of file wg06.h.

Provides raw F/T data to controllers.

Definition at line 200 of file wg06.h.

uint64_t WG06::ft_sample_count_ [private]

Counts number of ft sensor samples.

Definition at line 197 of file wg06.h.

bool WG06::has_accel_and_ft_ [private]

True if device has accelerometer and force/torque sensor.

Definition at line 182 of file wg06.h.

Definition at line 191 of file wg06.h.

Time diagnostics was last published.

Definition at line 188 of file wg06.h.

const unsigned WG06::MAX_FT_SAMPLES = 4 [static, private]

Definition at line 195 of file wg06.h.

const unsigned WG06::NUM_FT_CHANNELS = 6 [static, private]

Definition at line 196 of file wg06.h.

Set true where checksum error on pressure data is detected, cleared on reset.

Definition at line 184 of file wg06.h.

const unsigned WG06::PRESSURE_PHY_ADDR = 0x2200 [static, private]

Definition at line 168 of file wg06.h.

Definition at line 192 of file wg06.h.

Definition at line 170 of file wg06.h.

Realtime Publisher of RAW F/T data.

Definition at line 203 of file wg06.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


ethercat_hardware
Author(s): Rob Wheeler (email: wheeler@willowgarage.com), Maintained by Derek King (email: dking@willowgarage.com)
autogenerated on Fri Mar 1 16:52:17 2013