#include <ethercat_hardware/wg0x.h>
#include <ethercat_hardware/wg_soft_processor.h>
#include <pr2_msgs/PressureState.h>
#include <pr2_msgs/AccelerometerState.h>
#include <ethercat_hardware/RawFTData.h>
#include <geometry_msgs/WrenchStamped.h>
Go to the source code of this file.
Classes | |
struct | FTDataSample |
class | FTParamsInternal |
class | WG06 |
struct | WG06BigPressure |
struct | WG06Pressure |
struct | WG06StatusWithAccel |
struct | WG06StatusWithAccelAndFT |
Functions | |
struct WG06StatusWithAccel | __attribute__ ((__packed__)) |
Variables | |
class FTParamsInternal | __attribute__ |
uint32_t | accel_ [4] |
uint8_t | accel_count_ |
uint16_t | board_temperature_ |
uint16_t | bridge_temperature_ |
uint8_t | checksum_ |
int16_t | data_ [6] |
uint8_t | digital_out_ |
int32_t | encoder_count_ |
int32_t | encoder_index_pos_ |
uint8_t | encoder_status_ |
uint8_t | ft_sample_count_ |
FTDataSample | ft_samples_ [4] |
uint16_t | l_finger_tip_ [22] |
int16_t | measured_current_ |
uint8_t | mode_ |
int16_t | motor_voltage_ |
uint16_t | num_encoder_errors_ |
uint16_t | packet_count_ |
uint8_t | pad_ |
WG06Pressure | pressure_ |
int16_t | programmed_current_ |
int16_t | programmed_pwm_value_ |
uint16_t | r_finger_tip_ [22] |
uint8_t | sample_count_ |
static const unsigned | SIZE =61 |
uint16_t | supply_voltage_ |
uint32_t | timestamp_ |
uint8_t | unused1 |
int32_t | unused2 |
int32_t | unused3 |
uint8_t | unused4 [3] |
uint16_t | vhalf_ |
struct WG06StatusWithAccel __attribute__ | ( | (__packed__) | ) |
WG06 __attribute__ |
FTDataSample ft_samples_[4] |
WG06Pressure pressure_ |