From sdk-wiki
Controlling the Vacuum Gripper
This is the main API for interacting with Baxter's vacuum grippers, and is instantiated by:
from baxter_interface import Gripper
right_gripper = Gripper('right')
left_gripper = Gripper('left')
Its main uses are:
- Sending suck/release commands to the gripper
- Querying the state/properties of the gripper
- Reacting to grippers being plugged/unplugged
- And controlling aspects of how the gripper acts (vacuum threshold, etc.)
Reading the Vacuum Gripper Sensor
The vacuum gripper sensor falls under the Analog IO category in baxter_interface. To read the vacuum sensor, choose either left_vacuum_sensor_analog, right_vacuum_sensor_analog
as your component when initializing AnalogIO
:
Inside an init'd shell:
[baxter - http://p12345:11311] foo@bar:~/ros_ws$ python
>>> import rospy, baxter_interface
>>> rospy.init_node("vacuum_test")
>>> l_vacuum_sensor = baxter_interface.AnalogIO('left_vacuum_sensor_analog')
To query the sensor's state:
>>> l_vacuum_sensor.state()
11.0
Alternatively, it is possible to query the vacuum sensor from either of these ROS topics:
/robot/analog_io/<left\right>_vacuum_sensor_analog/state
/robot/analog_io/<left\right>_vacuum_sensor_analog/value_uint32
eg.
$ rostopic echo /robot/analog_io/left_vacuum_sensor_analog/state
---
timestamp:
secs: 1418760984
nsecs: 575399546
value: 20.0
isInputOnly: True
---
timestamp:
secs: 1418760984
nsecs: 585399929
value: 19.0
isInputOnly: True
---
These values being output via Python and ROS are analog values being read from the vacuum sensor. They can range from 0-255
, and the breakdown is as follows:
Value Range | Meaning |
0-46
|
The vacuum gripper is likely not attached to an object |
47-175
|
The vacuum is likely attached to an object (usually around 150 when grasping)
|
176+
|
There is likely a short between 5V and signal on the sensor |