#include <ArGripper.h>
Public Types | |
enum | Type { QUERYTYPE, GENIO, USERIO, GRIPPAC, NOGRIPPER } |
These are the types for the gripper. More... | |
Public Methods | |
ArGripper (ArRobot *robot, int gripperType=QUERYTYPE) | |
Constructor. More... | |
virtual | ~ArGripper (void) |
Destructor. | |
bool | gripOpen (void) |
Opens the gripper paddles. More... | |
bool | gripClose (void) |
Closes the gripper paddles. More... | |
bool | gripStop (void) |
Stops the gripper paddles. More... | |
bool | liftUp (void) |
Raises the lift to the top. More... | |
bool | liftDown (void) |
Lowers the lift to the bottom. More... | |
bool | liftStop (void) |
Stops the lift. More... | |
bool | gripperStore (void) |
Puts the gripper in a storage position. More... | |
bool | gripperDeploy (void) |
Puts the gripper in a deployed position, ready for use. More... | |
bool | gripperHalt (void) |
Halts the lift and the gripper paddles. More... | |
bool | gripPressure (int mSecIntervals) |
Sets the amount of pressure the gripper applies. More... | |
bool | liftCarry (int mSecIntervals) |
Raises the lift by a given amount of time. More... | |
bool | isGripMoving (void) |
Returns true if the gripper paddles are moving. More... | |
bool | isLiftMoving (void) |
Returns true if the lift is moving. More... | |
int | getGripState (void) |
Returns the state of the gripper paddles. More... | |
int | getPaddleState (void) |
Returns the state of each gripper paddle. More... | |
int | getBreakBeamState (void) |
Returns the state of the gripper's breakbeams. More... | |
bool | isLiftMaxed (void) |
Returns the state of the lift. More... | |
int | getType (void) |
Gets the type of the gripper. More... | |
void | setType (int type) |
Sets the type of the gripper. More... | |
long | getMSecSinceLastPacket (void) |
Gets the number of mSec since the last gripper packet. More... | |
int | getGraspTime (void) |
Gets the grasp time. More... | |
void | printState (void) |
logs the gripper state. | |
bool | packetHandler (ArRobotPacket *packet) |
Parses the gripper packet. | |
void | connectHandler (void) |
The handler for when the robot connects. |
The commands which start with grip are for the gripper paddles, the ones which start with lift are the for the lift, and the ones which start with gripper are for the entire unit.
|
These are the types for the gripper.
|
|
Constructor.
|
|
Returns the state of the gripper's breakbeams.
|
|
Gets the grasp time. If you are using this as anything other than GRIPPAC and you want to find out the grasp time again, just do a setType with QUERYTYPE and it will query the robot again and get the grasp time from the robot.
|
|
Returns the state of the gripper paddles.
|
|
Gets the number of mSec since the last gripper packet.
|
|
Returns the state of each gripper paddle.
|
|
Gets the type of the gripper.
|
|
Closes the gripper paddles.
|
|
Opens the gripper paddles.
|
|
Puts the gripper in a deployed position, ready for use.
|
|
Halts the lift and the gripper paddles.
|
|
Puts the gripper in a storage position.
|
|
Sets the amount of pressure the gripper applies.
|
|
Stops the gripper paddles.
|
|
Returns true if the gripper paddles are moving.
|
|
Returns the state of the lift.
|
|
Returns true if the lift is moving.
|
|
Raises the lift by a given amount of time.
|
|
Lowers the lift to the bottom.
|
|
Stops the lift.
|
|
Raises the lift to the top.
|
|
Sets the type of the gripper.
|