| Tekkotsu Homepage | Demos | Overview | Downloads | Dev. Resources | Reference | Credits |
PilotRequest.hGo 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; contents will be copied by Pilot::executeRequest 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 AngTwoPi targetHeading; //!< Heading on which we want to arrive at the target 00051 00052 ShapeRoot objectShape; //!< Object we want to push to the target 00053 MapBuilderRequest *objectExtractor; //!< Pointer to MapbuilderRequest for finding the object to be pushed; will be deleted by the Pilot 00054 ShapeRoot (*objectMatcher)(const ShapeRoot&); ///!< Finds the localShS object matching objectShape in worldShS 00055 00056 float obstacleInflation; //!< Inflation in mm of obstacle bounding shapes for path planning 00057 bool avoidCliffs; //!< If true, use IR to avoid walking off a cliff 00058 int cliffThreshold; //!< Maximum tolerable distance to the ground (millimeters) 00059 bool avoidObstacles; //!< If true, use rangefinder sensors to dynamically avoid obstacles (not yet implemented) 00060 int obstacleThreshold; //!< Minimum tolerable rangefinder distance to an obstacle (millimeters) 00061 LookoutTrackRequest *trackRequest; //!< Lookout request for tracking objects while walking 00062 00063 float displayParticles; //!< How many particles to display (number or percentage) as a single Graphics shape 00064 float displayIndividualParticles; //!< How many particles to display (number or percentage) as LocalizationParticle shapes 00065 bool displayPath; //!< If true, the planned path is displayed in the shape space 00066 bool displayTree; //!< If true, the RRT search tree is displayed in the world shape space 00067 bool displayObstacles; //!< If true, the obstacle boundaries used by the collision checker are displayed in the worls shape space 00068 unsigned int maxRRTIterations; //!< Maximum number of iterations for path planner RRT search 00069 bool executePath; //!< If true, the Pilot will execute the path it has planned; if false, it plans but does not execute 00070 std::vector<DualCoding::ShapeRoot> landmarks; //!< Vector of landmarks to use for localization 00071 00072 /* Target-related items from Somchaya Liemhetcharat's work; disabled for now 00073 float safeDistanceAroundTarget; //!< The distance to stay away from the target while circling 00074 AngSignPi subtendAngle; //!< The angle in which to subtend the target while circling 00075 AngSignPi approachAngle; //!< The angle in which to approach the desired position around the target 00076 Point positionRelativeToTarget; //!< The desired position around the target, relative to the target 00077 AngSignPi angleToPushTarget; //!< The angle in which to push the target 00078 void (*buildTargetParamsFn)(bool *buildFrontLeft, bool *buildFrontRight, bool *buildBackLeft, bool *buildBackRight, bool *lookAtCentroid, int *maxRetries); //!< function to return the parameters to build the target 00079 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 00080 */ 00081 00082 BehaviorBase* requestingBehavior; //!< Used to construct a PilotEvent to notify the requesting node of the results of this Pilot operation 00083 00084 PilotRequest& operator=(const PilotRequest &req); 00085 00086 bool operator==(const PilotRequest &other) const { return this == &other; } // needed for SignalTrans<PilotRequest> 00087 00088 private: 00089 unsigned int requestID; 00090 }; 00091 00092 } // namespace 00093 00094 #endif |
|
Tekkotsu v5.1CVS |
Generated Fri Mar 16 05:26:46 2012 by Doxygen 1.6.3 |