Public Member Functions | Public Attributes
pr2_hardware_interface::ActuatorState Class Reference

#include <hardware_interface.h>

List of all members.

Public Member Functions

 ActuatorState ()

Public Attributes

bool calibration_falling_edge_valid_
 Is the last_callibration_falling_edge_ field valid?
bool calibration_reading_
 the value of the last calibration reading: low (false) or high (true)
bool calibration_rising_edge_valid_
 Is the last_callibration_rising_edge_ field valid?
int device_id_
 Position in EtherCAT chain.
int encoder_count_
 The number of ticks as reported by the encoder.
double encoder_velocity_
 The velocity measured in encoder ticks per second.
bool halted_
 indicates if the motor is halted. A motor can be halted because of voltage or communication problems
bool is_enabled_
 Enable status.
double last_calibration_falling_edge_
 The position of the motor the last time the calibration switch went from high to low.
double last_calibration_rising_edge_
 The position of the motor the last time the calibration switch went from low to high.
double last_commanded_current_
 The current computed based on the effort specified in the ActuatorCommand (in amps)
double last_commanded_effort_
 The torque requested in the previous ActuatorCommand (in Nm)
double last_executed_current_
 The actual current requested after safety limits were enforced (in amps)
double last_executed_effort_
 The torque applied after safety limits were enforced (in Nm)
double last_measured_current_
 The measured current (in amps)
double last_measured_effort_
 The measured torque (in Nm)
double max_effort_
 Absolute torque limit for actuator (derived from motor current limit). (in Nm)
double motor_voltage_
 Motor voltage (in volts)
int num_encoder_errors_
 The number of invalid encoder signal transitions.
double position_
 The position of the motor (in radians)
ros::Duration sample_timestamp_
double timestamp_
double velocity_
 The velocity in radians per second.
double zero_offset_
 A bias applied to the position value when reported. This value is written once after calibration. The reported position is the hardware's actual position minus the zero offset.

Detailed Description

Definition at line 49 of file hardware_interface.h.


Constructor & Destructor Documentation

Definition at line 51 of file hardware_interface.h.


Member Data Documentation

Is the last_callibration_falling_edge_ field valid?

Definition at line 101 of file hardware_interface.h.

the value of the last calibration reading: low (false) or high (true)

Definition at line 99 of file hardware_interface.h.

Is the last_callibration_rising_edge_ field valid?

Definition at line 100 of file hardware_interface.h.

Position in EtherCAT chain.

Definition at line 92 of file hardware_interface.h.

The number of ticks as reported by the encoder.

Definition at line 94 of file hardware_interface.h.

The velocity measured in encoder ticks per second.

Definition at line 96 of file hardware_interface.h.

indicates if the motor is halted. A motor can be halted because of voltage or communication problems

Definition at line 106 of file hardware_interface.h.

Enable status.

Definition at line 105 of file hardware_interface.h.

The position of the motor the last time the calibration switch went from high to low.

Definition at line 103 of file hardware_interface.h.

The position of the motor the last time the calibration switch went from low to high.

Definition at line 102 of file hardware_interface.h.

The current computed based on the effort specified in the ActuatorCommand (in amps)

Definition at line 108 of file hardware_interface.h.

The torque requested in the previous ActuatorCommand (in Nm)

Definition at line 112 of file hardware_interface.h.

The actual current requested after safety limits were enforced (in amps)

Definition at line 109 of file hardware_interface.h.

The torque applied after safety limits were enforced (in Nm)

Definition at line 113 of file hardware_interface.h.

The measured current (in amps)

Definition at line 110 of file hardware_interface.h.

The measured torque (in Nm)

Definition at line 114 of file hardware_interface.h.

Absolute torque limit for actuator (derived from motor current limit). (in Nm)

Definition at line 116 of file hardware_interface.h.

Motor voltage (in volts)

Definition at line 118 of file hardware_interface.h.

The number of invalid encoder signal transitions.

Definition at line 120 of file hardware_interface.h.

The position of the motor (in radians)

Definition at line 95 of file hardware_interface.h.

The time at which actuator state was measured, relative to the time the ethercat process was started. Timestamp value is not synchronised with wall time and may be different for different actuators. For Willow Garage motor controllers, timestamp is made when actuator data is sampled. sample_timestamp_ will provide better accuracy than ros::Time::now() or robot->getTime() when using a time difference in calculations based on actuator variables.

Definition at line 83 of file hardware_interface.h.

The time at which this actuator state was measured (in seconds). This value should be same as sample_timestamp_.toSec() for Willow Garage devices. The timestamp_ variable is being kept around for backwards compatibility, new controllers should use sample_timestamp_ instead.

Definition at line 90 of file hardware_interface.h.

The velocity in radians per second.

Definition at line 97 of file hardware_interface.h.

A bias applied to the position value when reported. This value is written once after calibration. The reported position is the hardware's actual position minus the zero offset.

Definition at line 122 of file hardware_interface.h.


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


pr2_hardware_interface
Author(s): Eric Berger berger@willowgarage.com
autogenerated on Thu Dec 12 2013 12:03:52