pr2_gripper_sensor_msgs

Summary

pr2_gripper_sensor_msgs
Version:

1.0.9

Description:

The pr2_gripper_sensor_msgs package contains various actions and messages that are used in the pr2_gripper_sensor* packages. The structure of the API used by pr2_gripper_sensor_action, and pr2_gripper_sensor_controller packages is as follows: Users will send a goal to an Action in the message format of PR2Gripper*Command (where * replaces the name of the particular Action from pr2_gripper_sensor_action). Feedback and Result information for the action is then returned in the format of PR2Gripper*Data.

Maintainers:
  • Devon Ash <dash AT clearpathrobotics DOT com>
Licenses:
  • BSD
Urls:
  • website<None>
Authors:
  • Joe Romano
BuildDepends:
BuildtoolDepends:
 
BuildExportDepends:
 
ExecDepends:
Exports:
  • <cpp cflags=”-I${prefix}/msg/cpp”/>

Types

Message types

pr2_gripper_sensor_msgs/PR2GripperGrabCommand
Field:
  • hardness_gain (float64) –

The gain to use to evaluate how hard an object should be grasped after it is contacted. This is based on hardness estimation as outlined in TRO paper (see wiki).

Try 0.03

Units (N/(m/s^2))

# The gain to use to evaluate how hard an object should be
# grasped after it is contacted. This is based on hardness
# estimation as outlined in TRO paper (see wiki).
# 
# Try 0.03
#
# Units (N/(m/s^2))
float64 hardness_gain
pr2_gripper_sensor_msgs/PR2GripperSlipServoData
Field:
  • stamp (time) –
  • deformation (float64) –
  • left_fingertip_pad_force (float64) –
  • right_fingertip_pad_force (float64) –
  • joint_effort (float64) –
  • slip_detected (bool) –
  • deformation_limit_reached (bool) –
  • fingertip_force_limit_reached (bool) –
  • gripper_empty (bool) –
  • rtstate (pr2_gripper_sensor_msgs/PR2GripperSensorRTState) –

time the data was recorded at

# 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
pr2_gripper_sensor_msgs/PR2GripperSensorRawData
Field:
  • stamp (time) –
  • left_finger_pad_force (float64) –
  • right_finger_pad_force (float64) –
  • left_finger_pad_force_filtered (float64) –
  • right_finger_pad_force_filtered (float64) –
  • left_finger_pad_forces[22] (float64) –
  • right_finger_pad_forces[22] (float64) –
  • left_finger_pad_forces_filtered[22] (float64) –
  • right_finger_pad_forces_filtered[22] (float64) –
  • acc_x_raw (float64) –
  • acc_y_raw (float64) –
  • acc_z_raw (float64) –
  • acc_x_filtered (float64) –
  • acc_y_filtered (float64) –
  • acc_z_filtered (float64) –
  • left_contact (bool) –
  • right_contact (bool) –

NOTE: This message is only for debugging purposes. It is not intended for API usage - and is not published under release code.

Standard ROS header

# NOTE: This message is only for debugging purposes. It is not intended for API usage - and is not published under release code.

# Standard ROS header
time stamp

# corrected for zero contact
float64 left_finger_pad_force
float64 right_finger_pad_force

# filtered values : high pass filter at 5 Hz after correcting for zero contact
float64 left_finger_pad_force_filtered
float64 right_finger_pad_force_filtered

# corrected for zero contact
float64[22] left_finger_pad_forces
float64[22] right_finger_pad_forces

# filtered values : high pass filter at 5 Hz after correcting for zero contact
float64[22] left_finger_pad_forces_filtered
float64[22] right_finger_pad_forces_filtered

# raw acceleration values
float64 acc_x_raw
float64 acc_y_raw
float64 acc_z_raw

# filtered acceleration values
float64 acc_x_filtered
float64 acc_y_filtered
float64 acc_z_filtered

# boolean variables indicating whether contact exists or not
bool left_contact
bool right_contact
pr2_gripper_sensor_msgs/PR2GripperGrabData
Field:

the control state of our realtime controller

# the control state of our realtime controller
PR2GripperSensorRTState rtstate
pr2_gripper_sensor_msgs/PR2GripperSlipServoCommand

this command is currently blank, but may see additional variable additions in the future

see the param server documentation for a list of variables that effect slip servo performance

# this command is currently blank, but may see additional variable
# additions in the future

# see the param server documentation for a list of variables that effect
# slip servo performance
pr2_gripper_sensor_msgs/PR2GripperFindContactData
Field:
  • stamp (time) –
  • contact_conditions_met (bool) –
  • left_fingertip_pad_contact (bool) –
  • right_fingertip_pad_contact (bool) –
  • left_fingertip_pad_force (float64) –
  • right_fingertip_pad_force (float64) –
  • joint_position (float64) –
  • joint_effort (float64) –
  • rtstate (pr2_gripper_sensor_msgs/PR2GripperSensorRTState) –

Time the data was recorded at

# Time the data was recorded at
time stamp

# true when our contact conditions have been met
# (see PR2GripperFindContact command)
bool contact_conditions_met

# the finger contact conditions 
# true if the finger experienced a contact event
#
# contact events are defined as contact with the fingerpads
# as either steady-state or high-freq force events
bool left_fingertip_pad_contact
bool right_fingertip_pad_contact

# 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 joint position (m)
float64 joint_position

# the virtual (parallel) joint effort (N)
float64 joint_effort

# the control state of our realtime controller
PR2GripperSensorRTState rtstate
pr2_gripper_sensor_msgs/PR2GripperFindContactCommand
Field:
  • zero_fingertip_sensors (bool) –
  • contact_conditions (int8) –
Constant:
  • BOTH (int8):0
  • LEFT (int8):1
  • RIGHT (int8):2
  • EITHER (int8):3

set true if you want to calibrate the fingertip sensors on the start of the find_contact action. While this is not necessary (and the default value will not calibrate the sensors) for best performance it is recommended that you set this to true each time you are calling find_contact and are confident the fingertips are not touching anything NOTE: SHOULD ONLY BE TRUE WHEN BOTH FINGERS ARE TOUCHING NOTHING

# set true if you want to calibrate the fingertip sensors on the start
# of the find_contact action. While this is not necessary (and
# the default value will not calibrate the sensors) for best 
# performance it is recommended that you set this to true each time 
# you are calling find_contact and are confident the fingertips are 
# not touching anything
# NOTE: SHOULD ONLY BE TRUE WHEN BOTH FINGERS ARE TOUCHING NOTHING
bool zero_fingertip_sensors

# the finger contact conditions that determine what our goal is
# Leaving this field blank will result in the robot closing until
# contact on BOTH fingers is achieved
int8 contact_conditions

# predefined values for the above contact_conditions variable
int8 BOTH = 0   # both fingers must make contact
int8 LEFT = 1   # just the left finger 
int8 RIGHT = 2  # just the right finger
int8 EITHER = 3 # either finger, we don't care which
pr2_gripper_sensor_msgs/PR2GripperEventDetectorData
Field:
  • stamp (time) –
  • trigger_conditions_met (bool) –
  • slip_event (bool) –
  • acceleration_event (bool) –
  • acceleration_vector[3] (float64) –

Time the data was recorded at

# Time the data was recorded at
time stamp

# true if the trigger conditions have been met 
# (see PR2GripperEventDetectorCommand)
bool trigger_conditions_met

# true if the pressure sensors detected a slip event
# slip events occur when the finger pressure sensors
# high-freq. content exceeds the slip_trigger_magnitude variable
# (see PR2GripperEventDetectorCommand)
bool slip_event

# true if the hand-mounted accelerometer detected a contact acceleration
# acceleration events occur when the palm accelerometer
# high-freq. content exceeds the acc_trigger_magnitude variable
# (see PR2GripperEventDetectorCommand)
bool acceleration_event

# the high-freq acceleration vector that was last seen (x,y,z)
float64[3] acceleration_vector
pr2_gripper_sensor_msgs/PR2GripperForceServoData
Field:

Time the data was recorded at

# 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
pr2_gripper_sensor_msgs/PR2GripperReleaseData
Field:

the control state of our realtime controller

# the control state of our realtime controller
PR2GripperSensorRTState rtstate
pr2_gripper_sensor_msgs/PR2GripperSensorRTState
Field:
  • realtime_controller_state (int8) –
Constant:
  • DISABLED (int8):0
  • POSITION_SERVO (int8):3
  • FORCE_SERVO (int8):4
  • FIND_CONTACT (int8):5
  • SLIP_SERVO (int8):6

the control state of our realtime controller

# the control state of our realtime controller
int8 realtime_controller_state

# predefined values to indicate our realtime_controller_state
int8 DISABLED = 0
int8 POSITION_SERVO = 3
int8 FORCE_SERVO = 4
int8 FIND_CONTACT = 5
int8 SLIP_SERVO = 6
pr2_gripper_sensor_msgs/PR2GripperReleaseCommand
Field:

the event conditions we would like to trigger the robot to release on

# the event conditions we would like to trigger the robot to release on
PR2GripperEventDetectorCommand event
pr2_gripper_sensor_msgs/PR2GripperForceServoCommand
Field:
  • fingertip_force (float64) –

the amount of fingertip force (in Newtons) to apply. NOTE: the joint will squeeze until each finger reaches this level values < 0 (opening force) are ignored

10 N can crack an egg or crush a soda can. 15 N can firmly pick up a can of soup. Experiment on your own.

# the amount of fingertip force (in Newtons) to apply.
# NOTE: the joint will squeeze until each finger reaches this level
# values < 0 (opening force) are ignored
#
# 10 N can crack an egg or crush a soda can.
# 15 N can firmly pick up a can of soup.
# Experiment on your own.
#
float64 fingertip_force
pr2_gripper_sensor_msgs/PR2GripperEventDetectorCommand
Field:
  • trigger_conditions (int8) –
  • acceleration_trigger_magnitude (float64) –
  • slip_trigger_magnitude (float64) –
Constant:
  • FINGER_SIDE_IMPACT_OR_ACC (int8):0
  • SLIP_AND_ACC (int8):1
  • FINGER_SIDE_IMPACT_OR_SLIP_OR_ACC (int8):2
  • SLIP (int8):3
  • ACC (int8):4

state variable that defines what events we would like to trigger on Leaving this field blank will result in the robot triggering when anything touches the sides of the finger or an impact is detected with the hand/arm.

# state variable that defines what events we would like to trigger on
# Leaving this field blank will result in the robot triggering when 
# anything touches the sides of the finger or an impact is detected
# with the hand/arm.
int8 trigger_conditions
# definitions for our various trigger_conditions values
# trigger on either acceleration contact or finger sensor side impact
int8 FINGER_SIDE_IMPACT_OR_ACC = 0
# tigger once  both slip and acceleration signals occur
int8 SLIP_AND_ACC = 1 
#  trigger on either slip, acceleration, or finger sensor side impact
int8 FINGER_SIDE_IMPACT_OR_SLIP_OR_ACC = 2
# trigger only on slip information
int8 SLIP = 3
# trigger only on acceleration contact information
int8 ACC = 4 


# the amount of acceleration to trigger on (acceleration vector magnitude)
# Units = m/s^2
# The user needs to be concerned here about not setting the trigger too
# low so that is set off by the robot's own motions.
#
# For large rapid motions, say by a motion planner, 5 m/s^2 is a good level
# For small delicate controlled motions this can be set MUCH lower (try 2.0)
#
# NOTE: When moving the gripper joint (opening/closing the grippr)
# the high gearing of the PR2 gripper causes large acceleration vibrations
# which will cause triggering to occur. This is a known drawback of the PR2.
#
# NOTE: Leaving this value blank will result in a 0 m/s^2 trigger. If you
# are using a trigger_conditions value that returns on acceleration contact
# events then it will immediately exceed your trigger and return
float64 acceleration_trigger_magnitude


# the slip detector gain to trigger on (either finger) : try 0.01
# higher values decrease slip sensitivty (to a point)
# lower values increase sensitivity (to a point)
#
# NOTE: Leaving this value blank will result in the most sensitive slip level.
float64 slip_trigger_magnitude
pr2_gripper_sensor_msgs/PR2GripperPressureData
Field:
  • pressure_left[22] (float64) –
  • pressure_right[22] (float64) –
  • rostime (float64) –

Note: This message is intended for internal package use only and is NOT a part of the public API. This data is not publicaly published in ROS.

the pressure array for the left and right fingers

# Note: This message is intended for internal package use only and is NOT a part of the public API. This data is not publicaly published in ROS.

# the pressure array for the left and right fingers
float64[22] pressure_left
float64[22] pressure_right

float64 rostime

Action types

pr2_gripper_sensor_msgs/PR2GripperRelease
Field (Goal):
Field (Result):
Field (Feedback):
 

goal

#goal
PR2GripperReleaseCommand command
---
#result
PR2GripperReleaseData data
---

#feedback
PR2GripperReleaseData data
pr2_gripper_sensor_msgs/PR2GripperFindContact
Field (Goal):
Field (Result):
Field (Feedback):
 
  • data

goal

# Contact action used to close fingers and find object contacts 
# quickly while still stopping fast in real-time to not damage 
# objects

#goal
PR2GripperFindContactCommand command
---
#results
PR2GripperFindContactData data
---
# feedback
PR2GripperFindContactData data
pr2_gripper_sensor_msgs/PR2GripperGrab
Field (Goal):
Field (Result):
Field (Feedback):
 

goal

#goal
PR2GripperGrabCommand command
---
#result
PR2GripperGrabData data
---

#feedback
PR2GripperGrabData data
pr2_gripper_sensor_msgs/PR2GripperEventDetector
Field (Goal):
Field (Result):
Field (Feedback):
 
  • data

goal

# Event Detector action used to tell detect events happening on the 
# palm mounted accelerometer and finger pressure sensors

#goal
PR2GripperEventDetectorCommand command
---
#results
PR2GripperEventDetectorData data
---
# feedback
PR2GripperEventDetectorData data
pr2_gripper_sensor_msgs/PR2GripperSlipServo
Field (Goal):
Field (Result):
Field (Feedback):
 
  • data

goals

# Action to launch the gripper into slip servoing mode 

#goals
PR2GripperSlipServoCommand command
---

#result
PR2GripperSlipServoData data

---

#feedback
PR2GripperSlipServoData data
pr2_gripper_sensor_msgs/PR2GripperForceServo
Field (Goal):
Field (Result):
Field (Feedback):
 
  • data

goals

# Action to launch the gripper into force servoing mode 

#goals
PR2GripperForceServoCommand command
---

#result
PR2GripperForceServoData data

---

#feedback
PR2GripperForceServoData data