File: pr2_gripper_sensor_msgs/PR2GripperForceServoData.msg
# Time the data was recorded at
time stamp
# the force experienced by the finger Pads (N)
# NOTE:this ignores data from the edges of the finger pressure
float64 left_fingertip_pad_force
float64 right_fingertip_pad_force
# the current gripper virtual parallel joint effort (in N)
float64 joint_effort
# true when the gripper is no longer moving
# and we have reached the desired force level
bool force_achieved
# the control state of our realtime controller
PR2GripperSensorRTState rtstate
Expanded Definition
time stamp
float64 left_fingertip_pad_force
float64 right_fingertip_pad_force
float64 joint_effort
bool force_achieved
PR2GripperSensorRTState rtstate
int8 DISABLED=0
int8 POSITION_SERVO=3
int8 FORCE_SERVO=4
int8 FIND_CONTACT=5
int8 SLIP_SERVO=6
int8 realtime_controller_state