rapid
A ROS robotics library.
|
High-level interface for a PR2's gripper. More...
#include <gripper.h>
Public Member Functions | |
bool | StartOpening () |
Starts opening the gripper. More... | |
bool | StartClosing () |
Starts closing the gripper. More... | |
bool | StartClosing (double max_effort) |
Starts closing the gripper with a given maximum effort. More... | |
bool | IsDone () const |
Returns true if the gripper is done opening or closing. More... | |
void | Cancel () |
Stops the gripper's opening or closing movement. More... | |
Static Public Member Functions | |
static Gripper | Left () |
Returns a Gripper object for the PR2's left gripper. More... | |
static Gripper | Right () |
Returns a Gripper object for the PR2's right gripper. More... | |
High-level interface for a PR2's gripper.
Example:
void rapid::pr2::Gripper::Cancel | ( | ) |
Stops the gripper's opening or closing movement.
bool rapid::pr2::Gripper::IsDone | ( | ) | const |
Returns true if the gripper is done opening or closing.
|
static |
Returns a Gripper object for the PR2's left gripper.
|
static |
Returns a Gripper object for the PR2's right gripper.
bool rapid::pr2::Gripper::StartClosing | ( | ) |
Starts closing the gripper.
bool rapid::pr2::Gripper::StartClosing | ( | double | max_effort | ) |
Starts closing the gripper with a given maximum effort.
[in] | max_effort | The maximum amount of force to use, in Newtons. |
bool rapid::pr2::Gripper::StartOpening | ( | ) |
Starts opening the gripper.