Tekkotsu Homepage
Demos
Overview
Downloads
Dev. Resources
Reference
Credits

PilotRequest.h

Go to the documentation of this file.
00001 //-*-c++-*-
00002 #ifndef INCLUDED_PilotRequest_h_
00003 #define INCLUDED_PilotRequest_h_
00004 
00005 #include "DualCoding/ShapeRoot.h"
00006 #include "Behaviors/BehaviorBase.h"
00007 #include "Motion/WaypointList.h"
00008 
00009 #include "PilotTypes.h"
00010 
00011 namespace DualCoding {
00012 
00013 class MapBuilderRequest;
00014 class LookoutTrackRequest;
00015 
00016 //! Request to the @a Pilot for motion or navigation.
00017 class PilotRequest {
00018   friend class Pilot;
00019 
00020  public:
00021 
00022   //! Constructor
00023   PilotRequest(PilotTypes::RequestType_t _type = PilotTypes::noRequest);
00024 
00025   PilotRequest(const PilotRequest &req);
00026 
00027   PilotTypes::RequestType_t getRequestType() const { return requestType; }
00028 
00029   PilotTypes::RequestType_t requestType; //!< Type of pilot request
00030   float dx; //!< Forward distance in mm (negative means go backward)
00031   float dy; //!< Sideways distance in mm (positive to the left)
00032   float da; //!< Rotation angle in radians (positive is counterclockwise)
00033   float forwardSpeed; //!< Translation speed in mm/sec for @a dx or @a dy
00034   float strafeSpeed; //!< Sideways translational speed used for setVelocity
00035   float turnSpeed; //!< Rotational speed in radians/sec for @a da
00036   std::string walkParameters; // !< Name of walk parameter file to load
00037   PilotTypes::CollisionAction_t collisionAction;  //!< What to do about collisions
00038 
00039   WaypointList waypointList; //!< Waypoint list for waypointWalk
00040   bool clearWaypoints;  //!< If true, the waypointList will be cleared before appending new waypoints
00041 
00042   MapBuilderRequest *landmarkExtractor; //!< pointer to MapBuilderRequest used to find landmarks; will be deleted by the Pilot
00043   bool (*landmarkExitTest)(); //!< Should return true if there are enough landmarks to localize
00044 
00045   MapBuilderRequest *searchObjectExtractor; //!< MapBuilderRequest to be used for visual search
00046   bool (*searchExitTest)(); //!< If true, terminate search and post a completion event
00047   AngSignPi searchRotationAngle; //!< Angle to rotate body to continue a visual search
00048 
00049   ShapeRoot targetShape; //!< Shape to walk to
00050   fmat::Column<3> baseOffset; //!< Point in the base reference frame to bring to the target location
00051   AngTwoPi targetHeading; //!< Heading on which we want to arrive at the target
00052   float gateLength; //!< Distance between the gate point and the target point when targetHeading or baseOffset used
00053 
00054   ShapeRoot objectShape; //!< Object we want to push to the target
00055   MapBuilderRequest *objectExtractor; //!< Pointer to MapbuilderRequest for finding the object to be pushed; will be deleted by the Pilot
00056   ShapeRoot (*objectMatcher)(const ShapeRoot&); //!< Finds the localShS object matching objectShape in worldShS
00057   MapBuilderRequest *acquireExtractor; //!< Pointer to MapBuilderRequest to check if we have acquired the object
00058   bool (*acquireTest)(const ShapeRoot&); //!< Returns true if vision confirms that we have successfully acquired the object (e.g., for pushing)
00059 
00060   bool allowBackwardMotion; //!< True if the robot should avoid large turns by walking backwards if distance is short
00061   float maxBackwardDistance; //!< Maximum allowable distance to walk backward instead of turning around
00062 
00063   void (*pathEditor)(std::vector<PilotTypes::NodeValue_t> *pathResult, PilotRequest &req);
00064   void (*planEditor)(PilotTypes::NavigationPlan &plan, PilotRequest &req);
00065 
00066   float obstacleInflation; //!< Inflation in mm of obstacle bounding shapes for path planning
00067   bool avoidCliffs; //!< If true, use IR to avoid walking off a cliff
00068   int cliffThreshold; //!< Maximum tolerable distance to the ground (millimeters)
00069   bool avoidObstacles; //!< If true, use rangefinder sensors to dynamically avoid obstacles (not yet implemented)
00070   int obstacleThreshold; //!< Minimum tolerable rangefinder distance to an obstacle (millimeters)
00071   LookoutTrackRequest *trackRequest; //!< Lookout request for tracking objects while walking
00072 
00073   float displayParticles; //!< How many particles to display (number or percentage) as a single Graphics shape
00074   float displayIndividualParticles; //!< How many particles to display (number or percentage) as LocalizationParticle shapes
00075   bool displayPath; //!< If true, the planned path is displayed in the shape space
00076   bool displayTree; //!< If true, the RRT search tree is displayed in the world shape space
00077   bool displayObstacles; //!< If true, the obstacle boundaries used by the collision checker are displayed in the world shape space
00078   bool autoDisplayObstacles; //!< If true, the obstacle boundaries used by the collision checker are displayed in the world shape space automatically if path planning fails
00079   unsigned int maxRRTIterations; //!< Maximum number of iterations for path planner RRT search
00080   bool executePath;  //!< If true, the Pilot will execute the path it has planned; if false, it plans but does not execute
00081   std::vector<DualCoding::ShapeRoot> landmarks; //!< Vector of specific landmarks to use for localization, overriding the default
00082 
00083   /* Target-related items from Somchaya Liemhetcharat's work; disabled for now
00084   float safeDistanceAroundTarget; //!< The distance to stay away from the target while circling
00085   AngSignPi subtendAngle; //!< The angle in which to subtend the target while circling
00086   AngSignPi approachAngle; //!< The angle in which to approach the desired position around the target
00087   Point positionRelativeToTarget; //!< The desired position around the target, relative to the target
00088   AngSignPi angleToPushTarget; //!< The angle in which to push the target
00089   void (*buildTargetParamsFn)(bool *buildFrontLeft, bool *buildFrontRight, bool *buildBackLeft, bool *buildBackRight, bool *lookAtCentroid, int *maxRetries); //!< function to return the parameters to build the target
00090   MapBuilderRequest* (*buildTargetMapBuilderRequestFn)(Point point); //!< function to return a dynamically-constructed MapBuilderRequest, given a point to look at, which BuildTarget will use to build the target
00091   */
00092 
00093   BehaviorBase* requestingBehavior;  //!< Used to construct a PilotEvent to notify the requesting node of the results of this Pilot operation
00094   
00095   PilotRequest& operator=(const PilotRequest &req);
00096 
00097   bool operator==(const PilotRequest &other) const { return this == &other; } // needed for SignalTrans<PilotRequest>
00098 
00099 private:
00100   unsigned int requestID;
00101 };
00102 
00103 } // namespace
00104 
00105 #endif

Tekkotsu v5.1CVS
Generated Mon May 9 04:58:46 2016 by Doxygen 1.6.3