Tekkotsu Homepage
Demos
Overview
Downloads
Dev. Resources
Reference
Credits

XWalkParameters.h

Go to the documentation of this file.
00001 //-*-c++-*-
00002 #ifndef INCLUDED_XWalkParameters_h_
00003 #define INCLUDED_XWalkParameters_h_
00004 
00005 #include "Shared/plist.h"
00006 
00007 //! Parameters used by XWalkMC to control gait
00008 /*! One instance of this class is a public superclass which clients can modify directly, and
00009  *  a second instance is stored internally by XWalkMC which allows it to smoothly transition
00010  *  parameter values when they are updated.  (See XWalkMC::ParameterTransition) */
00011 class XWalkParameters : public virtual plist::Dictionary {
00012 protected:
00013   static const float EPSILON; //!< limit of resolution for various computations
00014   
00015 public:
00016   //! constructor, sets default values
00017   XWalkParameters()
00018   : plist::Dictionary(), groundPlane(4,0,false), gravityVector(3,0,false),
00019   offsetX(0), offsetY(0), offsetA(0), resetOnStop(true), frictionCoef(0), strideLenX(100), strideLenY(60), adaptiveLegOrder(true), rotateBodyMotion(true), transitionDuration(1500),
00020   bounce(), sway(), surge(), legParams(NumLegs), nonLegJoints()
00021   {
00022     init();
00023   }
00024   
00025   //! copy constructor, forwards to operator=
00026   XWalkParameters(const XWalkParameters& p) 
00027   : plist::Dictionary(), groundPlane(4,0,false), gravityVector(3,0,false),
00028   offsetX(0), offsetY(0), offsetA(0), resetOnStop(true), frictionCoef(0), strideLenX(100), strideLenY(60), adaptiveLegOrder(true), rotateBodyMotion(true), transitionDuration(1500),
00029   bounce(), sway(), surge(), legParams(NumLegs), nonLegJoints()
00030   {
00031     init();
00032     *this = p;
00033   }
00034   
00035   //! projects point to ground plane along gravity vector
00036   static void projectToGround(const fmat::Column<3>& ground, float height, const fmat::Column<3>& gravity, fmat::Column<3>& tgt);
00037   
00038   //! converts the gravity and ground configuration parameters to fmat data structures for further calculations
00039   /*! @a gravity will be normalized, @a ground will just be the first three terms of #groundPlane */
00040   void packGroundGravity(const fmat::SubVector<3>& ground, const fmat::SubVector<3> gravity) const;
00041   
00042   float getMaxXVel() const; //!< returns fastest possible foward velocity given the current parameters (mm/s)
00043   float getMaxYVel() const; //!< returns fastest possible sideways velocity given the current parameters (mm/s)
00044   float getMaxAVel() const; //!< returns fastest possible rotational velocity given the current parameters (rad/s)
00045   
00046   fmat::Column<2> computeNeutralPos(unsigned int leg) const; //!< returns center point of stride
00047   
00048   // ****** BODY PARAMETERS ******
00049   // *** Position ***
00050   
00051   //! equation of the ground plane relative to the base frame (in millimeters)
00052   /*! The equation is of the form @f$p_1x + p_2y + p_3z = p_4@f$, relative to the base frame, the first three parameters should be normalized.
00053    *  See also #gravityVector. */
00054   plist::ArrayOf<plist::Primitive<float> > groundPlane;
00055   
00056   //! Vector indicating direction of gravity's pull, relative to the ground plane normal vector; this influences the projection of the foot positions onto the ground plane, magnitude is arbitrary
00057   /*! This vector is added to the normal vector to the ground plane from the body frame origin.  Thus,
00058    *  leaving this vector at (0,0,0) means that the gravity vector will always point straight into the ground,
00059    *  and adjusting the ground plane will change the attitude of the body without affecting foot positions.
00060    *  However, adjusting this instead of the groundPlane adjusts feet positions while keeping body parallel
00061    *  to the ground.  Adjusting both is necessarily if you want to keep the body Z-axis aligned with gravity
00062    *  while walking uphill.  */
00063   plist::ArrayOf<plist::Primitive<float> > gravityVector;
00064   
00065   //! Bias the position of the body relative to the ground (in millimeters), so increasing this parameter moves the robot forward, parallel to the ground.
00066   /*! See also each leg's stanceWidth, which if changed en masse can provide the same adjustment parallel to the base frame instead of ground plane */
00067   plist::Primitive<float> offsetX;
00068   
00069   //! Bias the position of the body relative to the ground (in millimeters), so increasing this parameter moves the robot left, parallel to the ground.
00070   /*! See also each leg's strideBias, which if changed en masse can provide the same adjustment parallel to the base frame instead of ground plane */
00071   plist::Primitive<float> offsetY;
00072   
00073   //! Bias the orientation of the body relative to the ground (in radians), so increasing this parameter turns the robot counter-clockwise
00074   plist::Primitive<float> offsetA;
00075   
00076   //! Causes the feet to redistribute to their central positions when motion stops.
00077   /*! Looks better, but actually a little inefficient when you start walking again */
00078   plist::Primitive<bool> resetOnStop;
00079   
00080   //! Coefficient of friction with the ground (aka µ), limits the amount of non-normal force which can be applied
00081   plist::Primitive<float> frictionCoef;
00082   
00083   
00084   // *** Motion ***
00085   
00086   //! The size of step to take with each leg (all legs have the same period and travel same speed, so must have the same length of stride)
00087   plist::Primitive<float> strideLenX;
00088   
00089   //! The size of step to take with each leg (all legs have the same period and travel same speed, so must have the same length of stride)
00090   plist::Primitive<float> strideLenY;
00091   
00092   //! Whether to re-order the leg flights based on direction of motion
00093   plist::Primitive<bool> adaptiveLegOrder;
00094   
00095   //! Whether to rotate the sway and surge motions to match direction of motion
00096   plist::Primitive<bool> rotateBodyMotion;
00097   
00098   //! How much time to use getting into initial position, or when parameters change (milliseconds)
00099   plist::Primitive<unsigned int> transitionDuration;
00100   
00101   //! Specifies parameters for shifting the body position while in motion
00102   class SinusoidalParameters : public virtual plist::Dictionary {
00103   public:
00104     plist::Primitive<float> magnitude; //!< distance of motion (peak-to-center)
00105     plist::Primitive<float> phase; //!< offsets phase within stride (0-1)
00106     plist::Primitive<float> baseline; //!< offsets the median value to be oscillated about
00107     plist::Primitive<float> freqScale; //!< multiplies the frequency of the oscillation, so '2' would repeat the oscillation twice within a cycle
00108     plist::Primitive<int> legLink; //!< if a valid leg index (i.e. non-negative, less than number of legs), indicates the leg phase to use instead of global phase
00109     //! constructor
00110     SinusoidalParameters() : plist::Dictionary(), magnitude(0), phase(0), baseline(0), freqScale(2), legLink(-1) {
00111       addEntry("Magnitude",magnitude);
00112       addEntry("Phase",phase);
00113       addEntry("Baseline",baseline);
00114       addEntry("FreqScale",freqScale);
00115       addEntry("LegLink",legLink);
00116       setLoadSavePolicy(FIXED,SYNC);
00117     }
00118     inline float operator()(float globPhase, float* legPhases) {
00119       if(magnitude==0)
00120         return baseline;
00121       unsigned int leg = static_cast<unsigned int>(legLink);
00122       if(leg<NumLegs)
00123         return baseline-magnitude*std::cos((legPhases[leg] - phase)*freqScale*2*float(M_PI));
00124       else
00125         return baseline-magnitude*std::cos((globPhase - phase)*freqScale*2*float(M_PI));
00126     }
00127   };
00128   SinusoidalParameters bounce; //!< moves the body up and down
00129   SinusoidalParameters sway; //!< moves the body left and right
00130   SinusoidalParameters surge; //!< moves the body forward and back
00131   
00132   // ****** PER-LEG PARAMETERS ******
00133   //! Specifies parameters for each leg
00134   class LegParameters : public virtual plist::Dictionary {
00135   public:
00136     plist::Primitive<bool> usable; //!< if false, disables the leg from motion by the walk
00137     // *** Position ***
00138     plist::Primitive<float> stanceWidth; //!< 'y' position of the foot during forward travel, relative to body/base frame
00139     plist::Primitive<float> strideBias; //!< 'x' position of the foot during sideways travel, relative to 'x' position of first leg joint in body/base frame
00140     plist::Primitive<float> strideMargin; //!< distance to leave between this foot and the next when lowering
00141     // *** Motion ***
00142     plist::Primitive<float> flightHeight; //!< the minimum height above ground while in flight
00143     plist::Primitive<float> flightPhase; //!< the offset of this leg within the walk cycle (0-1)
00144     plist::Primitive<unsigned int> flightDuration; //!< the time to take in the air, returning a leg to the front of its stroke (ms)
00145     plist::Primitive<unsigned int> raiseDuration; //!< the time to take lifting a leg from the ground before flight (ms)
00146     plist::Primitive<unsigned int> lowerDuration; //!< the time to lower a leg back to the ground after flight (ms)
00147     //! constructor
00148     LegParameters() : plist::Dictionary(), usable(true), stanceWidth(250), strideBias(0), strideMargin(75), flightHeight(35), flightPhase(0), flightDuration(400), raiseDuration(250), lowerDuration(250) {
00149       addEntry("Usable",usable);
00150       addEntry("StanceWidth",stanceWidth);
00151       addEntry("StrideBias",strideBias);
00152       addEntry("StrideMargin",strideMargin);
00153       addEntry("FlightHeight",flightHeight);
00154       addEntry("FlightPhase",flightPhase);
00155       addEntry("FlightDuration",flightDuration);
00156       addEntry("RaiseDuration",raiseDuration);
00157       addEntry("LowerDuration",lowerDuration);
00158       setLoadSavePolicy(FIXED,SYNC);
00159     }
00160     //! returns sum of raise, flight, and lower durations
00161     unsigned int totalDuration() const { return raiseDuration + flightDuration + lowerDuration; }
00162   };
00163   plist::ArrayOf<LegParameters> legParams;
00164   
00165   plist::DictionaryOf<SinusoidalParameters> nonLegJoints;
00166   
00167 protected:
00168   void init() {
00169     addEntry("GroundPlane",groundPlane,
00170          "Specifies the ground plane relative to the base frame (in millimeters),\n"
00171          "of the form: p₁·x + p₂·y + p₃·z = p₄\n"
00172          "The first 3 entries should be normalized, so that the fourth is the\n"
00173          "distance from the origin.");
00174     addEntry("GravityVector",gravityVector,
00175          "Specifies an offset to be added to the GroundPlane normal vector to specify\n"
00176          "the direction of gravity.  This influences the projection of the foot positions\n"
00177          "onto the ground plane, magnitude is arbitrary.");
00178     addEntry("OffsetX",offsetX,"Bias the position of the body relative to the ground (in millimeters), so increasing this parameter moves the robot forward, parallel to the ground.");
00179     addEntry("OffsetY",offsetY,"Bias the position of the body relative to the ground (in millimeters), so increasing this parameter moves the robot left, parallel to the ground.");
00180     addEntry("OffsetA",offsetA,"Bias the orientation of the body relative to the ground (in radians), so increasing this parameter turns the robot counter-clockwise.");
00181     addEntry("ResetOnStop",resetOnStop,"Causes the feet to redistribute to their central positions when motion stops.");
00182     addEntry("FrictionCoefficient",frictionCoef,"Coefficient of friction with the ground (aka µ), limits the amount of non-normal force which can be applied");
00183     addEntry("StrideLengthX",strideLenX,"The size of forward (x-axis) step (mm) to take with each leg (all legs have the same period and travel same speed, so must have the same length of stride)");
00184     addEntry("StrideLengthY",strideLenY,"The size of sideways (y-axis) step (mm) to take with each leg (all legs have the same period and travel same speed, so must have the same length of stride)");
00185     addEntry("AdaptiveLegOrder",adaptiveLegOrder,"If true, re-orders the leg flights based on direction of motion");
00186     addEntry("RotateBodyMotion",rotateBodyMotion,"If true, rotate the sway and surge motions to match direction of motion");
00187     addEntry("TransitionDuration",transitionDuration,"How much time to use getting into initial position, or when parameters change (milliseconds)");
00188     addEntry("Bounce",bounce,"Movement up and down while walking");
00189     addEntry("Sway",sway,"Movement left and right while walking");
00190     addEntry("Surge",surge,"Movement forward and backward while walking");
00191     addEntry("LegParameters",legParams);
00192     addEntry("NonLegJoints",nonLegJoints,"Controls motion of non-leg joints, e.g. swaying arms to balance legs");
00193     nonLegJoints.setLoadSavePolicy(SYNC,SYNC);
00194     setLoadSavePolicy(FIXED,SYNC);
00195     groundPlane[2]=1;
00196     groundPlane[3]=0;
00197     float dur = 1.f/(NumLegs+NumWheels);
00198     float phase = 0;
00199     for(unsigned int i=NumLegs-1; i<NumLegs; i-=4) {
00200       if(i+1<NumLegs) {
00201         legParams[i+1].flightPhase=phase;
00202         phase+=dur;
00203       }
00204       legParams[i].flightPhase=phase;
00205       phase+=dur;
00206     }
00207     for(unsigned int i=NumLegs-2; i<NumLegs; i-=4) {
00208       legParams[i].flightPhase=phase;
00209       phase+=dur;
00210       if(i-1U<NumLegs) {
00211         legParams[i-1U].flightPhase=phase;
00212         phase+=dur;
00213       }
00214     }
00215   }
00216 
00217   float nominalPeriod() const;
00218   float minPeriod() const;
00219 };
00220 
00221 /*! @file
00222  * @brief Defines XWalkParameters, which provide configuration settings for XWalkMC
00223  * @author Ethan Tira-Thompson (ejt) (Creator)
00224  */
00225 
00226 #endif

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