pr2_gripper_sensor_msgs/PR2GripperSlipServoData Message

File: pr2_gripper_sensor_msgs/PR2GripperSlipServoData.msg

# time the data was recorded at
time stamp

# the amount of deformation from action start (in meters)
float64 deformation

# the force experinced 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 virtual parallel joint effort of the gripper (in N)
float64 joint_effort

# true if the object recently slipped
bool slip_detected

# true if we are at or exceeding the deformation limit
# (see wiki page and param server for more info)
bool deformation_limit_reached

# true if we are at or exceeding our force 
# (see wiki page and param server for more info)
bool fingertip_force_limit_reached

# true if the controller thinks the gripper is empty
# (see wiki page for more info)
bool gripper_empty

# the control state of our realtime controller
PR2GripperSensorRTState rtstate

Expanded Definition

time stamp
float64 deformation
float64 left_fingertip_pad_force
float64 right_fingertip_pad_force
float64 joint_effort
bool slip_detected
bool deformation_limit_reached
bool fingertip_force_limit_reached
bool gripper_empty
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