Tekkotsu Homepage
Demos
Overview
Downloads
Dev. Resources
Reference
Credits

Grasper Class Reference

The Grasper is the member of the Tekkotsu Crew responsible for arm-based manipulation. More...

#include <Grasper.h>

Inheritance diagram for Grasper:

Detailed Description

The Grasper is the member of the Tekkotsu Crew responsible for arm-based manipulation.

The Grasper can make requests to the Pilot, MapBuilder, and Lookout.

The quintessential Grasper operation is moveTo, which picks up an object, transports it to a destination, and deposits it there. Depending on the type of robot, arm, and gripper, and the locations of the object and destination point, a grasper request might involve moving the robot's body as well as the arm.

The moveTo operation has six phases:

  • Approach: Get the robot close to the object. Then position the arm so it's ready to grab the object.
  • Grasp: Close the fingers around the object and verify that it is under control of the gripper. May involve moving the object and visual verification.
  • Transport: Carry or drag the object to a location near the destination. May involve lifting the object, or repositioning the arm prior to moving the body.
  • Deliver: Place the object at its destination.
  • Release: Let go of the object and verify that it is placed properly.
  • Withdraw: retract the arm and/or move the body away from the object.

Definition at line 71 of file Grasper.h.

List of all members.

Classes

class  ArmGrasp
 Close fingers to grasp the object. More...
class  ArmNudge
 Move the object to test that it was grasped successfully. More...
class  ArmPulse
 Set or clear gripper pulsing to prevent load errors. More...
class  ArmRaise
 Raise the object for transport. More...
class  CloseTheGripper
 Close the gripper. More...
class  DoArmApproach
 Execute arm motion to get fingers around the object. More...
class  DoArmDeliver
 Execute arm motion to deposit the object at its destination. More...
class  DoBodyApproach
 Execute body motion to approach the object. More...
class  DoBodyApproach2
 For Calliope2SP: move body instead of arm to acquire the object. More...
class  DoBodyApproach3
 For Calliope2SP: move body instead of arm to acquire the object. More...
class  DoBodyTransport
 Execute body move for dropoff. More...
class  DoWithdraw
 DoWithdraw from the object. More...
class  FindObj
 Re-acquire object on local map after moving the body. More...
class  FingersApproach
 Open fingers far enough to accomodate object. More...
class  GrasperFailed
 Report failure of the grasper request via a GrasperEvent. More...
class  GrasperSucceeded
 Report successful completion of the grasper request via a GrasperEvent. More...
class  IfRequestIs
class  MoveArm
 Moves the body. More...
class  NextRequest
 Move on to the next grasper request. More...
class  OpenTheGripper
 Open the gripper. More...
class  PathPlanConstrained
 Plan a constrained path. More...
class  PathPlanToRest
 Plan a path to the rest state. More...
class  PlanArmApproach
 Plan arm motion to get fingers around the object. More...
class  PlanArmDeliver
 Plan arm move to dropoff location. More...
class  PlanBodyApproach
 Plan body motion to approach the object. More...
class  PlanBodyTransport
 Plan body move to dropoff location. More...
class  ReleaseArm
 Release the object. More...
class  Rest
 Moves the arm to the rest state. More...
class  SetJoint
 Set joint to specified angle. More...
class  SignalGraspError
 Signal the failure of a grasp sub-statemachine via a signalTrans. More...
class  Verify
 Verify that object is grasped. More...

Public Types

typedef ShapeSpacePlanner3DR
< NumArmJoints-2 > 
ArmPlanner
typedef PlannerObstacle3D PlannerObstacleG
typedef ArmPlanner::NodeType_t NodeType_t
typedef NodeType_t::NodeValue_t NodeValue_t
typedef unsigned int GrasperVerbosity_t

Public Member Functions

 Grasper ()
virtual void setup ()
 This is called by start() when it should setup the network of subnodes (if any).
virtual void preStart ()
 Called by start() before the doStart(), allows superclasses to do some initialization startup preceeding subclass customization.
unsigned int executeRequest (const GrasperRequest &req, BehaviorBase *requestingBehavior)
 User-level interface for queueing a request to the Grasper.
void executeRequest ()
 Executes the next pending request, i.e., the one at the front of the queue.
void dispatch ()
 Dispatches on the request type, running the appropriate state machine; called by executeRequest().
void doStop ()
 Delegate function for subclasses to be notified when the behavior starts up.
MotionManager::MC_ID getArmId () const
void computeGoalStates (IKSolver::Point &toPt, std::vector< std::pair< float, float > > &rangesX, std::vector< std::pair< float, float > > &rangesY, std::vector< std::pair< float, float > > &rangesZ, float resolution, std::vector< NodeValue_t > &goals, const IKSolver::Point &offset)
 Generates potential goal states around a point, rotating the approach orientation.
void checkGoalCandidate (const IKSolver::Point &offset, const IKSolver::Rotation &ori, KinematicJoint *effector, const IKSolver::Point &position, std::vector< NodeValue_t > &goals)
 Helper function for computeGoalStates.

Static Public Member Functions

static void getCurrentState (NodeValue_t &current, KinematicJoint *endEffector=NULL)
 Gets current state of robot's arm from the end effector given.

Static Public Attributes

static const unsigned int numPlannerJoints = NumArmJoints-2
static const GrasperVerbosity_t GVstart = 1<<0
static const GrasperVerbosity_t GVexecuteRequest = 1<<1
static const GrasperVerbosity_t GVnumObstacles = 1<<2
static const GrasperVerbosity_t GVexecutePath = 1<<3
static const GrasperVerbosity_t GVcomputeGoals = 1<<4
static const GrasperVerbosity_t GVsetJoint = 1<<5
static GrasperRequestcurReq = NULL
 The request itself.
static GrasperVerbosity_t verbosity = -1U

Protected Attributes

std::queue< GrasperRequest * > requests
 Queue of pending Grasper requests.
unsigned int idCounter
 Counter for assigning a unique id to each Grasper request.
MotionManager::MC_ID armId
 id for shared ArmMC

Private Member Functions

GenericRRTBase::PlannerResult2D planBodyPath (const Point &targPt, AngTwoPi approachOrientation, const fmat::Column< 3 > &baseOffset, Shape< AgentData > &pose, float radius, bool isFinalApproach)
 Plan an approach or transport path for the body.
 Grasper (const Grasper &o)
 Copy constructor; do not use.
void operator= (const Grasper &o)
 Assignment operator; do not use.

Private Attributes

StateNodestartmain_
 The main reach-grasp-move-release-rest sequence.

Member Typedef Documentation

typedef ShapeSpacePlanner3DR<NumArmJoints-2> Grasper::ArmPlanner

Definition at line 74 of file Grasper.h.

typedef unsigned int Grasper::GrasperVerbosity_t

Definition at line 101 of file Grasper.h.

Definition at line 98 of file Grasper.h.

Definition at line 99 of file Grasper.h.

Definition at line 75 of file Grasper.h.


Constructor & Destructor Documentation

Grasper::Grasper (  ) 

Definition at line 752 of file Grasper.h.

Grasper::Grasper ( const Grasper o  )  [private]

Copy constructor; do not use.


Member Function Documentation

void Grasper::checkGoalCandidate ( const IKSolver::Point offset,
const IKSolver::Rotation ori,
KinematicJoint effector,
const IKSolver::Point position,
std::vector< NodeValue_t > &  goals 
)

Helper function for computeGoalStates.

Definition at line 1218 of file Grasper.cc.

Referenced by computeGoalStates().

void Grasper::computeGoalStates ( IKSolver::Point toPt,
std::vector< std::pair< float, float > > &  rangesX,
std::vector< std::pair< float, float > > &  rangesY,
std::vector< std::pair< float, float > > &  rangesZ,
float  resolution,
std::vector< NodeValue_t > &  goals,
const IKSolver::Point offset 
)

Generates potential goal states around a point, rotating the approach orientation.

Definition at line 1151 of file Grasper.cc.

void Grasper::dispatch (  ) 

Dispatches on the request type, running the appropriate state machine; called by executeRequest().

Definition at line 1318 of file Grasper.cc.

Referenced by executeRequest().

void Grasper::doStop (  )  [virtual]

Delegate function for subclasses to be notified when the behavior starts up.

May be overridden to cleanup when the behavior is shutting down. However events will automatically be unsubscribed, and by using addMotion(), motions will automatically be removed by stop(), so you may not need any cleanup.

Reimplemented from BehaviorBase.

Definition at line 1364 of file Grasper.cc.

void Grasper::executeRequest (  ) 

Executes the next pending request, i.e., the one at the front of the queue.

Definition at line 1279 of file Grasper.cc.

Referenced by executeRequest().

unsigned int Grasper::executeRequest ( const GrasperRequest req,
BehaviorBase requestingBehavior 
)

User-level interface for queueing a request to the Grasper.

Definition at line 1260 of file Grasper.cc.

void Grasper::getCurrentState ( NodeValue_t current,
KinematicJoint endEffector = NULL 
) [static]

Gets current state of robot's arm from the end effector given.

Definition at line 1142 of file Grasper.cc.

Referenced by Grasper::PathPlanToRest::doStart(), Grasper::PathPlanConstrained::doStart(), and Grasper::PlanArmApproach::doStart().

void Grasper::operator= ( const Grasper o  )  [private]

Assignment operator; do not use.

GenericRRTBase::PlannerResult2D Grasper::planBodyPath ( const Point &  targPt,
AngTwoPi  approachOrientation,
const fmat::Column< 3 > &  baseOffset,
Shape< AgentData > &  pose,
float  radius,
bool  isFinalApproach = true 
) [private]

Plan an approach or transport path for the body.

Definition at line 25 of file Grasper.cc.

virtual void Grasper::preStart (  )  [virtual]

Called by start() before the doStart(), allows superclasses to do some initialization startup preceeding subclass customization.

For robustness to future change, subclasses should be sure to call the superclass implementation.

Reimplemented from BehaviorBase.

Definition at line 895 of file Grasper.h.

virtual void Grasper::setup (  )  [virtual]

This is called by start() when it should setup the network of subnodes (if any).

Reimplemented from StateNode.

Definition at line 757 of file Grasper.h.


Member Data Documentation

id for shared ArmMC

Definition at line 941 of file Grasper.h.

Referenced by doStop(), getArmId(), and setup().

Definition at line 106 of file Grasper.h.

Referenced by computeGoalStates().

Definition at line 105 of file Grasper.h.

Referenced by Grasper::MoveArm::doStart().

Definition at line 103 of file Grasper.h.

Referenced by executeRequest().

Definition at line 104 of file Grasper.h.

const GrasperVerbosity_t Grasper::GVsetJoint = 1<<5 [static]

Definition at line 107 of file Grasper.h.

Referenced by Grasper::SetJoint::moveJoint().

const GrasperVerbosity_t Grasper::GVstart = 1<<0 [static]

Definition at line 102 of file Grasper.h.

Referenced by preStart().

unsigned int Grasper::idCounter [protected]

Counter for assigning a unique id to each Grasper request.

Definition at line 940 of file Grasper.h.

Referenced by executeRequest().

const unsigned int Grasper::numPlannerJoints = NumArmJoints-2 [static]

Definition at line 76 of file Grasper.h.

Referenced by checkGoalCandidate(), Grasper::MoveArm::executeMove(), and getCurrentState().

std::queue<GrasperRequest*> Grasper::requests [protected]

Queue of pending Grasper requests.

Definition at line 939 of file Grasper.h.

Referenced by executeRequest(), and preStart().

The main reach-grasp-move-release-rest sequence.

Definition at line 748 of file Grasper.h.

Referenced by dispatch(), doStop(), and setup().


The documentation for this class was generated from the following files:

Tekkotsu v5.1CVS
Generated Mon May 9 04:59:08 2016 by Doxygen 1.6.3