#include <hardware_interface.h>
Public Member Functions | |
ActuatorState () | |
Public Attributes | |
bool | calibration_falling_edge_valid_ |
Is the last_callibration_falling_edge_ field valid? More... | |
bool | calibration_reading_ |
the value of the last calibration reading: low (false) or high (true) More... | |
bool | calibration_rising_edge_valid_ |
Is the last_callibration_rising_edge_ field valid? More... | |
int | device_id_ |
Position in EtherCAT chain. More... | |
int | encoder_count_ |
The number of ticks as reported by the encoder. More... | |
double | encoder_velocity_ |
The velocity measured in encoder ticks per second. More... | |
bool | halted_ |
indicates if the motor is halted. A motor can be halted because of voltage or communication problems More... | |
bool | is_enabled_ |
Enable status. More... | |
double | last_calibration_falling_edge_ |
The position of the motor the last time the calibration switch went from high to low. More... | |
double | last_calibration_rising_edge_ |
The position of the motor the last time the calibration switch went from low to high. More... | |
double | last_commanded_current_ |
The current computed based on the effort specified in the ActuatorCommand (in amps) More... | |
double | last_commanded_effort_ |
The torque requested in the previous ActuatorCommand (in Nm) More... | |
double | last_executed_current_ |
The actual current requested after safety limits were enforced (in amps) More... | |
double | last_executed_effort_ |
The torque applied after safety limits were enforced (in Nm) More... | |
double | last_measured_current_ |
The measured current (in amps) More... | |
double | last_measured_effort_ |
The measured torque (in Nm) More... | |
double | max_effort_ |
Absolute torque limit for actuator (derived from motor current limit). (in Nm) More... | |
double | motor_voltage_ |
Motor voltage (in volts) More... | |
int | num_encoder_errors_ |
The number of invalid encoder signal transitions. More... | |
double | position_ |
The position of the motor (in radians) More... | |
ros::Duration | sample_timestamp_ |
double | timestamp_ |
double | velocity_ |
The velocity in radians per second. More... | |
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. More... | |
Definition at line 81 of file hardware_interface.h.
|
inline |
Definition at line 115 of file hardware_interface.h.
bool pr2_hardware_interface::ActuatorState::calibration_falling_edge_valid_ |
Is the last_callibration_falling_edge_ field valid?
Definition at line 165 of file hardware_interface.h.
bool pr2_hardware_interface::ActuatorState::calibration_reading_ |
the value of the last calibration reading: low (false) or high (true)
Definition at line 163 of file hardware_interface.h.
bool pr2_hardware_interface::ActuatorState::calibration_rising_edge_valid_ |
Is the last_callibration_rising_edge_ field valid?
Definition at line 164 of file hardware_interface.h.
int pr2_hardware_interface::ActuatorState::device_id_ |
Position in EtherCAT chain.
Definition at line 156 of file hardware_interface.h.
int pr2_hardware_interface::ActuatorState::encoder_count_ |
The number of ticks as reported by the encoder.
Definition at line 158 of file hardware_interface.h.
double pr2_hardware_interface::ActuatorState::encoder_velocity_ |
The velocity measured in encoder ticks per second.
Definition at line 160 of file hardware_interface.h.
bool pr2_hardware_interface::ActuatorState::halted_ |
indicates if the motor is halted. A motor can be halted because of voltage or communication problems
Definition at line 170 of file hardware_interface.h.
bool pr2_hardware_interface::ActuatorState::is_enabled_ |
Enable status.
Definition at line 169 of file hardware_interface.h.
double pr2_hardware_interface::ActuatorState::last_calibration_falling_edge_ |
The position of the motor the last time the calibration switch went from high to low.
Definition at line 167 of file hardware_interface.h.
double pr2_hardware_interface::ActuatorState::last_calibration_rising_edge_ |
The position of the motor the last time the calibration switch went from low to high.
Definition at line 166 of file hardware_interface.h.
double pr2_hardware_interface::ActuatorState::last_commanded_current_ |
The current computed based on the effort specified in the ActuatorCommand (in amps)
Definition at line 172 of file hardware_interface.h.
double pr2_hardware_interface::ActuatorState::last_commanded_effort_ |
The torque requested in the previous ActuatorCommand (in Nm)
Definition at line 176 of file hardware_interface.h.
double pr2_hardware_interface::ActuatorState::last_executed_current_ |
The actual current requested after safety limits were enforced (in amps)
Definition at line 173 of file hardware_interface.h.
double pr2_hardware_interface::ActuatorState::last_executed_effort_ |
The torque applied after safety limits were enforced (in Nm)
Definition at line 177 of file hardware_interface.h.
double pr2_hardware_interface::ActuatorState::last_measured_current_ |
The measured current (in amps)
Definition at line 174 of file hardware_interface.h.
double pr2_hardware_interface::ActuatorState::last_measured_effort_ |
The measured torque (in Nm)
Definition at line 178 of file hardware_interface.h.
double pr2_hardware_interface::ActuatorState::max_effort_ |
Absolute torque limit for actuator (derived from motor current limit). (in Nm)
Definition at line 180 of file hardware_interface.h.
double pr2_hardware_interface::ActuatorState::motor_voltage_ |
Motor voltage (in volts)
Definition at line 182 of file hardware_interface.h.
int pr2_hardware_interface::ActuatorState::num_encoder_errors_ |
The number of invalid encoder signal transitions.
Definition at line 184 of file hardware_interface.h.
double pr2_hardware_interface::ActuatorState::position_ |
The position of the motor (in radians)
Definition at line 159 of file hardware_interface.h.
ros::Duration pr2_hardware_interface::ActuatorState::sample_timestamp_ |
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 147 of file hardware_interface.h.
double pr2_hardware_interface::ActuatorState::timestamp_ |
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 154 of file hardware_interface.h.
double pr2_hardware_interface::ActuatorState::velocity_ |
The velocity in radians per second.
Definition at line 161 of file hardware_interface.h.
double pr2_hardware_interface::ActuatorState::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.
Definition at line 186 of file hardware_interface.h.