Tekkotsu Homepage
Demos
Overview
Downloads
Dev. Resources
Reference
Credits

CMPackWalkMC.cc

Go to the documentation of this file.
00001 //This class is ported from Carnegie Mellon's 2001 Robosoccer entry,
00002 //and falls under their license:
00003 /*=========================================================================
00004  CMPack'02 Source Code Release for OPEN-R SDK v1.0
00005  Copyright (C) 2002 Multirobot Lab [Project Head: Manuela Veloso]
00006  School of Computer Science, Carnegie Mellon University
00007  -------------------------------------------------------------------------
00008  This software is distributed under the GNU General Public License,
00009  version 2.  If you do not have a copy of this licence, visit
00010  www.gnu.org, or write: Free Software Foundation, 59 Temple Place,
00011  Suite 330 Boston, MA 02111-1307 USA.  This program is distributed
00012  in the hope that it will be useful, but WITHOUT ANY WARRANTY,
00013  including MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
00014  -------------------------------------------------------------------------
00015  Additionally licensed to Sony Corporation under the following terms:
00016  
00017  This software is provided by the copyright holders AS IS and any
00018  express or implied warranties, including, but not limited to, the
00019  implied warranties of merchantability and fitness for a particular
00020  purpose are disclaimed.  In no event shall authors be liable for
00021  any direct, indirect, incidental, special, exemplary, or consequential
00022  damages (including, but not limited to, procurement of substitute
00023  goods or services; loss of use, data, or profits; or business
00024  interruption) however caused and on any theory of liability, whether
00025  in contract, strict liability, or tort (including negligence or
00026  otherwise) arising in any way out of the use of this software, even if
00027  advised of the possibility of such damage.
00028  =========================================================================
00029 */
00030 
00031 #define WALKMC_NO_WARN_NOOP
00032 #include "CMPackWalkMC.h"
00033 
00034 #include "Shared/WorldState.h"
00035 #include "Events/EventRouter.h"
00036 #include "Events/LocomotionEvent.h"
00037 #include "Wireless/Socket.h"
00038 #include "Shared/Config.h"
00039 
00040 #include "Motion/MotionManager.h"
00041 
00042 #if !defined(PLATFORM_APERIOS) && defined(TGT_HAS_LEGS)
00043 #  include "Kinematics.h"
00044 #  include "IPC/DriverMessaging.h"
00045 #endif
00046 
00047 #include <stdlib.h>
00048 #include <stdio.h>
00049 #include <iostream>
00050 #include <fcntl.h>
00051 #include <unistd.h>
00052 #include <fstream>
00053 #include <cmath>
00054 
00055 //#define BOUND_MOTION
00056 
00057 #ifdef TGT_HAS_LEGS
00058 const float CMPackWalkMC::MAX_DX   = 180;//225; // mm/sec
00059 const float CMPackWalkMC::MAX_DY   = 140;//170; // mm/sec
00060 const float CMPackWalkMC::MAX_DA   = 1.8f;//2.1; // rad/sec
00061 #else
00062 // Create robot
00063 const float CMPackWalkMC::MAX_DX   = 225; // mm/sec
00064 const float CMPackWalkMC::MAX_DY   = 0  ; // mm/sec
00065 const float CMPackWalkMC::MAX_DA   = 2.1f; // rad/sec
00066 #endif
00067 #ifdef TGT_HAS_WHEELS
00068 const float CMPackWalkMC::OPTIMAL_DA   = 0.9f; // rad/sec for Create: value that seems to give reasonably accurate odometry
00069 #endif
00070 const vector3d CMPackWalkMC::max_accel_xya(MAX_DX*2,MAX_DY*2,MAX_DA*2);
00071 
00072 
00073 unsigned int checksum(const char *data,int num); //!< computes a file checksum
00074 
00075 CMPackWalkMC::CMPackWalkMC(const char* pfile/*=NULL*/)
00076   : MotionCommand(), isPaused(false), wp(), cp(), body_loc(), body_angle(),
00077   acc_style(DEFAULT_ACCEL), step_count(-1), step_threshold(0), last_cycle(0),
00078   pos_delta(0,0,0), angle_delta(0), travelTime(get_time()),
00079   time(get_time()), TimeStep(FrameTime), slowmo(1.0f),
00080   CycleOffset(0), TimeOffset(0), NewCycleOffset(false),
00081   target_disp_xya(0,0,0), vel_xya(0,0,0), target_vel_xya(0,0,0), last_target_vel_xya(0,0,0)
00082 { init(pfile); }
00083 
00084 CMPackWalkMC::CalibrationParam::CalibrationParam() {
00085   for(unsigned int r=0; r<3; r++) {
00086     for(unsigned int c=0; c<11; c++)
00087       f_calibration[r][c]=b_calibration[r][c]=0;
00088     f_calibration[r][r]=b_calibration[r][r]=1;
00089   }
00090   for(unsigned int d=0; d<NUM_DIM; d++)
00091     max_accel[d]=0;
00092   max_vel[0]=max_vel[1]=MAX_DX;
00093   max_vel[2]=MAX_DY;
00094   max_vel[3]=MAX_DA;
00095 }
00096 
00097 
00098 void CMPackWalkMC::start() {
00099   MotionCommand::start();
00100   LocomotionEvent e(EventBase::locomotionEGID,getID(),EventBase::activateETID,0);
00101   e.setXYA((float)target_vel_xya.x, (float)target_vel_xya.y, (float)target_vel_xya.z);
00102   postEvent(e);
00103   travelTime=get_time();
00104 }
00105 
00106 void CMPackWalkMC::stop() {
00107   zeroVelocities();
00108   MotionCommand::stop();
00109 }
00110 
00111 void CMPackWalkMC::zeroVelocities() {
00112   unsigned int t=get_time();
00113   setTargetVelocity(0,0,0);
00114 #ifdef TGT_HAS_WHEELS
00115   for (unsigned int i = WheelOffset; i < WheelOffset + NumWheels; i++)
00116     motman->setOutput(this, i, 0.0f);
00117 #endif
00118   LocomotionEvent e(EventBase::locomotionEGID, getID(), EventBase::deactivateETID, t-travelTime); // velocities default to 0
00119   travelTime = t;
00120   postEvent(e);
00121 }
00122 
00123 
00124 
00125 void CMPackWalkMC::init(const char* pfile)
00126 {
00127 #ifdef TGT_HAS_LEGS
00128   //  RegInit();
00129   body_loc.init(vector3d(0,0,wp.body_height),vector3d(0,0,0));
00130   body_angle.init(vector3d(0,wp.body_angle,0),vector3d(0,0,0));
00131   
00132   for(unsigned int i=0; i<NumLegs; i++)
00133     legw[i].air = false;
00134   
00135   if(pfile!=NULL)
00136     loadFile(pfile);
00137   else
00138     loadFile(config->motion.walk.c_str());
00139   
00140   resetLegPos();
00141   
00142   //  cmds[HeadOffset+TiltOffset].set(.3333,1);
00143 #endif
00144 }
00145 
00146 int CMPackWalkMC::isDirty()
00147 {
00148   if(isPaused) return 0;
00149   if(step_count==0) return 0;
00150   if((target_vel_xya.x == 0) && (target_vel_xya.y == 0) && (target_vel_xya.z == 0)) {
00151     // we may stopping, but not stopped yet...
00152     if((vel_xya.x == 0) && (vel_xya.y == 0) && (vel_xya.z == 0))
00153       return 0;
00154   }
00155 #ifdef TGT_HAS_LEGS
00156   return JointsPerLeg*NumLegs;
00157 #elif defined(TGT_HAS_WHEELS)
00158   return NumWheels;
00159 #else
00160   return 0;
00161 #endif
00162 }
00163 
00164 unsigned int CMPackWalkMC::getBinSize() const {
00165   unsigned int used=0;
00166   used+=creatorSize("WalkMC-2.2");
00167   used+=sizeof(wp);
00168   used+=sizeof(cp);
00169   return used;  
00170 }
00171 
00172 unsigned int CMPackWalkMC::loadBuffer(const char buf[], unsigned int len, const char* filename) {
00173   enum {
00174     VER1, // original CMPack version
00175     VER2, // added calibration parameters
00176     VER3 // added diff drive and sag parameter
00177   } version;
00178   
00179   unsigned int origlen=len;
00180   if(checkCreatorInc("WalkMC-2.2",buf,len,false)) {
00181     version=VER3;
00182   } else if(checkCreatorInc("WalkMC",buf,len,false)) {
00183       sout->printf("Pre-2.2 release walk parameter file %s\n",filename);
00184     version=VER2;
00185   } else {
00186     // backwards compatability - if there's no creator code, just assume it's a straight WalkParam
00187     sout->printf("Assuming CMPack format walk parameter file %s\n",filename);
00188     version=VER1;
00189   }
00190   
00191   // Leg parameters
00192   for(unsigned int i=0; i<4; ++i) {
00193     if(!decodeInc(wp.leg[i].neutral.x,buf,len)) return 0;
00194     if(!decodeInc(wp.leg[i].neutral.y,buf,len)) return 0;
00195     if(!decodeInc(wp.leg[i].neutral.z,buf,len)) return 0;
00196     if(!decodeInc(wp.leg[i].lift_vel.x,buf,len)) return 0;
00197     if(!decodeInc(wp.leg[i].lift_vel.y,buf,len)) return 0;
00198     if(!decodeInc(wp.leg[i].lift_vel.z,buf,len)) return 0;
00199     if(!decodeInc(wp.leg[i].down_vel.x,buf,len)) return 0;
00200     if(!decodeInc(wp.leg[i].down_vel.y,buf,len)) return 0;
00201     if(!decodeInc(wp.leg[i].down_vel.z,buf,len)) return 0;
00202     if(!decodeInc(wp.leg[i].lift_time,buf,len)) return 0;
00203     if(!decodeInc(wp.leg[i].down_time,buf,len)) return 0;
00204   }
00205   // Body parameters
00206   if(!decodeInc(wp.body_height,buf,len)) return 0;
00207   if(!decodeInc(wp.body_angle,buf,len)) return 0;
00208   if(!decodeInc(wp.hop,buf,len)) return 0;
00209   if(!decodeInc(wp.sway,buf,len)) return 0;
00210   if(!decodeInc(wp.period,buf,len)) return 0;
00211   if(version<VER3) wp.useDiffDrive=0; else if(!decodeInc(wp.useDiffDrive,buf,len)) return 0;
00212   if(version<VER3) wp.sag=0; else if(!decodeInc(wp.sag,buf,len)) return 0;
00213   if(!decodeInc(wp.reserved,buf,len)) return 0;
00214   // Calibration parameters
00215   if(version<VER2) {
00216     cp=CalibrationParam();
00217   } else {
00218     for(unsigned int i=0; i<3; ++i)
00219       for(unsigned int j=0; j<11; ++j)
00220         if(!decodeInc(cp.f_calibration[i][j],buf,len)) return 0;
00221     for(unsigned int i=0; i<3; ++i)
00222       for(unsigned int j=0; j<11; ++j)
00223         if(!decodeInc(cp.b_calibration[i][j],buf,len)) return 0;
00224     for(unsigned int i=0; i<CalibrationParam::NUM_DIM; ++i)
00225       if(!decodeInc(cp.max_accel[i],buf,len)) return 0;
00226     for(unsigned int i=0; i<CalibrationParam::NUM_DIM; ++i)
00227       if(!decodeInc(cp.max_vel[i],buf,len)) return 0;
00228   }
00229   return origlen-len; 
00230 }
00231 
00232 unsigned int CMPackWalkMC::saveBuffer(char buf[], unsigned int len) const {
00233   unsigned int origlen=len;
00234   // Leg parameters
00235   if(!saveCreatorInc("WalkMC-2.2",buf,len)) return 0;
00236   for(unsigned int i=0; i<4; ++i) {
00237     if(!encodeInc(wp.leg[i].neutral.x,buf,len)) return 0;
00238     if(!encodeInc(wp.leg[i].neutral.y,buf,len)) return 0;
00239     if(!encodeInc(wp.leg[i].neutral.z,buf,len)) return 0;
00240     if(!encodeInc(wp.leg[i].lift_vel.x,buf,len)) return 0;
00241     if(!encodeInc(wp.leg[i].lift_vel.y,buf,len)) return 0;
00242     if(!encodeInc(wp.leg[i].lift_vel.z,buf,len)) return 0;
00243     if(!encodeInc(wp.leg[i].down_vel.x,buf,len)) return 0;
00244     if(!encodeInc(wp.leg[i].down_vel.y,buf,len)) return 0;
00245     if(!encodeInc(wp.leg[i].down_vel.z,buf,len)) return 0;
00246     if(!encodeInc(wp.leg[i].lift_time,buf,len)) return 0;
00247     if(!encodeInc(wp.leg[i].down_time,buf,len)) return 0;
00248   }
00249   // Body parameters
00250   if(!encodeInc(wp.body_height,buf,len)) return 0;
00251   if(!encodeInc(wp.body_angle,buf,len)) return 0;
00252   if(!encodeInc(wp.hop,buf,len)) return 0;
00253   if(!encodeInc(wp.sway,buf,len)) return 0;
00254   if(!encodeInc(wp.period,buf,len)) return 0;
00255   if(!encodeInc(wp.useDiffDrive,buf,len)) return 0;
00256   if(!encodeInc(wp.sag,buf,len)) return 0;
00257   if(!encodeInc(wp.reserved,buf,len)) return 0;
00258   // Calibration parameters
00259   for(unsigned int i=0; i<3; ++i)
00260     for(unsigned int j=0; j<11; ++j)
00261       if(!encodeInc(cp.f_calibration[i][j],buf,len)) return 0;
00262   for(unsigned int i=0; i<3; ++i)
00263     for(unsigned int j=0; j<11; ++j)
00264       if(!encodeInc(cp.b_calibration[i][j],buf,len)) return 0;
00265   for(unsigned int i=0; i<CalibrationParam::NUM_DIM; ++i)
00266     if(!encodeInc(cp.max_accel[i],buf,len)) return 0;
00267   for(unsigned int i=0; i<CalibrationParam::NUM_DIM; ++i)
00268     if(!encodeInc(cp.max_vel[i],buf,len)) return 0;
00269   return origlen-len; 
00270 }
00271 
00272 unsigned int CMPackWalkMC::loadFile(const char* filename) {
00273   return LoadSave::loadFile(config->motion.makePath(filename).c_str());
00274 }
00275 unsigned int CMPackWalkMC::saveFile(const char* filename) const {
00276   return LoadSave::saveFile(config->motion.makePath(filename).c_str());
00277 }
00278 
00279 void CMPackWalkMC::setTargetVelocity(double dx,double dy,double da) {
00280 #ifdef BOUND_MOTION
00281   da = bound(da, -cp.rotate_max_vel, cp.rotate_max_vel);
00282   double fa = 1.0 - fabs(da / cp.rotate_max_vel);
00283   
00284   vector2d v(dx>0?dx/cp.forward_max_vel:dx/cp.reverse_max_vel,dy/cp.strafe_max_vel);
00285   double l = v.length();
00286   if(l > 1) v /= l;
00287   
00288   dx = (dx>0?cp.forward_max_vel:cp.reverse_max_vel) * v.x * fa;
00289   dy = cp.strafe_max_vel * v.y * fa;
00290 #endif
00291   
00292 #ifdef TGT_HAS_WHEELS
00293   dy=0; // can't move sideways...
00294 #endif
00295   
00296   // static int myCounter = 0;
00297   // if ( (myCounter++ % 100) == 0 || dx != target_vel_xya.x )
00298   //   std::cout << "setTargetVelocity " << dx << ' ' << dy << ' ' << da << std::endl;
00299 
00300   // Modifiy the target velocity, but hold off on generating an event
00301   // until the changes are actually picked up by the motion system.
00302   target_vel_xya.set(dx,dy,da);
00303 }
00304 
00305 void CMPackWalkMC::setTargetVelocity(double vx,double vy,double va,double dur) {
00306   if(dur<=0) {
00307     setTargetVelocity(0,0,0);
00308     return;
00309   }
00310   setTargetVelocity(vx,vy,va);
00311 #if TGT_HAS_LEGS
00312   //compute the point in cycle of the mid-step
00313   float midsteps[NumLegs];
00314   for(unsigned int i=0; i<NumLegs; i++)
00315     midsteps[i] = (float)(wp.leg[i].down_time+wp.leg[i].lift_time)/2;
00316   //find the number of unique steps per cycle
00317   unsigned int steps_per_cycle=NumLegs;
00318   for(unsigned int i=0; int(i)<int(NumLegs)-1; i++) {
00319     //std::cout << "i=" << i << "\n";
00320     for(unsigned int j=i+1; j<NumLegs; j++) {
00321       if(midsteps[i]==midsteps[j]) {
00322         steps_per_cycle--;
00323         break;
00324       }
00325     }
00326   }
00327   step_count = std::max(1,static_cast<int>(dur/(wp.period/1000.0)*steps_per_cycle + 0.5));
00328 #elif TGT_HAS_WHEELS
00329   target_disp_xya.set(vx*dur,vy*dur,va*dur);
00330   // std::cout << "setTargetVelocity: target_disp_xya " << vx*dur << " " << vy*dur << " " << va*dur << std::endl;
00331   step_count=1;
00332 #else
00333   std::cout << "CMPackWalkMC::setTargetVelocity with duration undefined for this robot architecture.\n";
00334 #endif
00335 }
00336 
00337 void CMPackWalkMC::setTargetDisplacement(double dx, double dy, double da, double dur) {
00338   if(dur<0) {
00339     setTargetVelocity(0,0,0);
00340     return;
00341   }
00342   const float tx = std::abs((float)dx/getMaxXVel());
00343   const float ta = std::abs((float)da/getMaxAVel());
00344 #if TGT_HAS_LEGS
00345   const float ty = std::abs((float)dy/getMaxYVel());
00346   const double maxTime =  std::max<double>(dur,std::max(tx,std::max(ty,ta)));
00347   setTargetVelocity(dx/maxTime, dy/maxTime, da/maxTime, maxTime);
00348 #elif TGT_HAS_WHEELS
00349   (void)dy; // to avoid unused variable warning
00350   const double maxTime =  std::max<double>(dur,std::max(tx,ta));
00351   setTargetVelocity(dx/maxTime, 0, da/maxTime);
00352   target_disp_xya.set(dx,0,da);
00353   // std::cout << "setTargetDisplacement: target_disp_xya " << dx << " " << 0 << " " << da << std::endl;
00354   step_count=1;
00355 #else
00356   (void)tx; // avoid unused variable warnings
00357   (void)ta;
00358   std::cout << "CMPackWalkMC::setTargetDisplacement undefined for this robot architecture.\n";
00359 #endif
00360 }
00361 
00362 int CMPackWalkMC::updateOutputs() {
00363   if(!isDirty()) return 0;
00364   unsigned int curT=get_time();
00365   if ( fabs(target_vel_xya.z) < 1e-3 )
00366     target_vel_xya.z = 0;  // trying to waypointwalk backwards causes tiny oscillations in angular velocity
00367   // post a locomotion event if we are changing velocity by a nontrivial amount
00368   if ( last_target_vel_xya != target_vel_xya ) {
00369     last_target_vel_xya=target_vel_xya;
00370     LocomotionEvent e(EventBase::locomotionEGID,getID(),EventBase::statusETID,getTravelTime());
00371     e.setXYA((float)target_vel_xya.x, (float)target_vel_xya.y, (float)target_vel_xya.z);
00372     postEvent(e);
00373     travelTime=curT;
00374   }
00375   
00376 #if defined(TGT_HAS_LEGS)
00377   if(vel_xya.sqlength()==0) {
00378     // we had been stopped - better check someone else didn't move the legs while we weren't using them...
00379     resetLegPos(); 
00380   }
00381   
00382   float tm = TimeStep * slowmo / 1000;
00383   
00384   vector3d cal_target_vel_xya(target_vel_xya);
00385   if(target_vel_xya.x<0)
00386     cal_target_vel_xya.x/=cp.max_vel[CalibrationParam::reverse];
00387   else
00388     cal_target_vel_xya.x/=cp.max_vel[CalibrationParam::forward];
00389   cal_target_vel_xya.y/=cp.max_vel[CalibrationParam::strafe];
00390   cal_target_vel_xya.z/=cp.max_vel[CalibrationParam::rotate];
00391   if(cal_target_vel_xya.sqlength()>.0025) {
00392     if(target_vel_xya.x<0)
00393       applyCalibration(cp.b_calibration,target_vel_xya,cal_target_vel_xya);
00394     else
00395       applyCalibration(cp.f_calibration,target_vel_xya,cal_target_vel_xya);
00396   }
00397   
00398   if(step_count<0 && (acc_style==CALIBRATION_ACCEL || (acc_style==DEFAULT_ACCEL && !config->motion.inf_walk_accel))) {
00399     //software accel:
00400     vel_xya.x = bound(cal_target_vel_xya.x, vel_xya.x-max_accel_xya.x*tm, vel_xya.x+max_accel_xya.x*tm);
00401     vel_xya.y = bound(cal_target_vel_xya.y, vel_xya.y-max_accel_xya.y*tm, vel_xya.y+max_accel_xya.y*tm);
00402     vel_xya.z = bound(cal_target_vel_xya.z, vel_xya.z-max_accel_xya.z*tm, vel_xya.z+max_accel_xya.z*tm);
00403   } else {
00404     //no software accel:
00405     vel_xya=cal_target_vel_xya;
00406   }
00407   
00408   BodyPosition delta;
00409   delta.loc.set(vel_xya.x*tm,vel_xya.y*tm,0);
00410   delta.angle.set(0,0,vel_xya.z*tm);
00411   
00412   time=(int)(curT*slowmo);
00413   
00414   // tss "SmoothWalk" addition follows
00415   // If necessary, we compute a new TimeOffset here.
00416   if(NewCycleOffset) {
00417     TimeOffset = CycleOffset - time % wp.period;
00418     NewCycleOffset = false;
00419   }
00420   
00421   // Adjusted time--time adjusted for cycle matching
00422   int AdjustedTime = time + TimeOffset;
00423   
00424   // If walking speeds have dwindled down to zero, save our time offset from the beginning of the current walk cycle. Once we start walking again, we start up at the same offset to prevent jerky starts.
00425   if((vel_xya.x == 0) && (vel_xya.y == 0) && (vel_xya.z == 0)) {
00426     CycleOffset = AdjustedTime % wp.period;
00427     NewCycleOffset = true;
00428   }
00429   // tss "SmoothWalk" addition ends
00430   
00431 #ifndef PLATFORM_APERIOS
00432   bool contactChanged=false;
00433 #endif
00434   for(unsigned int frame=0; frame<NumFrames; frame++) {
00435     cal_target_vel_xya.rotate_z(-delta.angle.z);
00436     
00437     // incorporate movement delta
00438     angle_delta += (float)delta.angle.z;
00439     pos_delta += delta.loc.rotate_z(angle_delta);
00440     
00441     //    cout << "setup,,," << flush;
00442     
00443     // tss "SmoothWalk" modification follows
00444     // double cycle = (double)(time % wp.period) / wp.period;
00445     AdjustedTime = time + TimeOffset + (int)(frame*TimeStep*slowmo);
00446     double cycle = (double)(AdjustedTime % wp.period) / wp.period;
00447     
00448     if(step_count>0) {
00449       for(unsigned int i=0; i<NumLegs; i++){
00450         float midstep;
00451         if(step_threshold<=.5f)
00452           midstep=(float)(wp.leg[i].lift_time+(wp.leg[i].down_time-wp.leg[i].lift_time)*step_threshold*2);
00453         else
00454           midstep=(float)(wp.leg[i].down_time+(1-wp.leg[i].down_time+wp.leg[i].lift_time)*(step_threshold-.5)*2);
00455         midstep-=floorf(midstep);
00456         //cout << "leg "<<i<<": " <<AdjustedTime << ' ' << cycle << ' ' << last_cycle << ' ' << midstep << ' ' <<step_count ;
00457         bool above_last= (last_cycle<midstep);
00458         bool below_cur = (midstep<=cycle);
00459         bool wrap      = (cycle<last_cycle);
00460         //need any 2 of the conditions: above_last && below_cur || wrap && (above_last || below_cur)
00461         if(above_last+below_cur+wrap>1) { //we just completed a step
00462           step_count--;
00463           //cout << " -> " << step_count << endl;
00464           if(step_count==0) { //we're done, copy out any completed frames
00465             for(unsigned int f=0; f<frame; f++)
00466               for(unsigned int joint=LegOffset; joint<LegOffset+NumLegJoints; joint++)
00467                 motman->setOutput(this,joint,cmds[joint][f],f);
00468             CycleOffset = AdjustedTime % wp.period;
00469             NewCycleOffset = true;
00470             last_cycle=cycle;
00471             target_vel_xya.set(0,0,0);
00472             last_target_vel_xya=target_vel_xya;
00473             LocomotionEvent e(EventBase::locomotionEGID,getID(),EventBase::statusETID,getTravelTime());
00474             e.setXYA((float)target_vel_xya.x, (float)target_vel_xya.y, (float)target_vel_xya.z);
00475             //cout << e.getDescription(true) << endl;
00476             postEvent(e);
00477             postEvent(EventBase(EventBase::motmanEGID,getID(),EventBase::statusETID,getTravelTime()));
00478             //    cout << "WalkMC-done" << endl;
00479             return frame==0?0:NumLegs*JointsPerLeg;
00480           }
00481           break; //don't count legs moving in sync as two steps, only ever one step at a time
00482         }
00483         //cout << endl;
00484       }
00485     }
00486     
00487     
00488     double sway   = wp.sway*cos(2*M_PI*cycle);
00489     double hop    = wp.hop*sin(4*M_PI*cycle);
00490     double height = wp.body_height;
00491     BodyPosition nextpos;
00492     nextpos.loc.set(0,-sway,height+hop);
00493     nextpos.angle.set(0,wp.body_angle,0);
00494     
00495     //    cout << "loop,,," << flush;
00496     for(unsigned int i=0; i<NumLegs; i++){
00497       
00498       //interpret a down time before a lift time as a request to move the leg in reverse (has its uses)
00499       float lift_time=(float)wp.leg[i].lift_time;
00500       float down_time=(float)wp.leg[i].down_time;
00501       float dir=1;
00502       if(down_time==lift_time)
00503         dir=0;
00504       else if(down_time<lift_time) {
00505         lift_time=(float)wp.leg[i].down_time;
00506         down_time=(float)wp.leg[i].lift_time;
00507         dir=-1;
00508       }
00509       
00510       bool air = (cycle >= lift_time) && (cycle < down_time);
00511       double air_f = down_time - lift_time;
00512       double nextlegangles[JointsPerLeg];
00513       
00514       if(air != legw[i].air){
00515 #ifndef PLATFORM_APERIOS
00516         contactChanged=true;
00517 #endif
00518         if(air){
00519           /*
00520            cout << i << ":   ";
00521            cout << legpos[i].x << ' ' << legpos[i].y << ' ' << legpos[i].z << "  ->  ";
00522            GetLegAngles(nextlegangles,legpos[i],nextpos,i);
00523            for(unsigned int j=0; j<JointsPerLeg; j++)
00524            cout << nextlegangles[j] << ' ';
00525            cout << endl;
00526            */
00527           tm = wp.period/1000.f * 0.75f; //wtf is the 0.75 based on?  Don't ask me, i just work here! (ejt)
00528           vector3d vfp;
00529           double vfa;
00530           if(step_count<0 && (acc_style==CALIBRATION_ACCEL || (acc_style==DEFAULT_ACCEL && !config->motion.inf_walk_accel))) {
00531             //software accel:
00532             vfp.x = bound(cal_target_vel_xya.x, vel_xya.x-max_accel_xya.x*tm, vel_xya.x+max_accel_xya.x*tm);
00533             vfp.y = bound(cal_target_vel_xya.y, vel_xya.y-max_accel_xya.y*tm, vel_xya.y+max_accel_xya.y*tm);
00534             vfa   = bound(cal_target_vel_xya.z, vel_xya.z-max_accel_xya.z*tm, vel_xya.z+max_accel_xya.z*tm);
00535           } else {
00536             //no software accel:
00537             vfp.x=cal_target_vel_xya.x;
00538             vfp.y=cal_target_vel_xya.y;
00539             vfa=cal_target_vel_xya.z;
00540           }
00541           
00542           vfp.z = 0.0;
00543           double b = (wp.period/1000.0) * (1.0 - air_f) / 2.0;
00544           vector3d target;
00545           if(wp.useDiffDrive) {
00546             float rot = (float)(vfa/cp.max_vel[CalibrationParam::rotate]);
00547             if((i&1)==0)
00548               rot=-rot;
00549             vfp.x += cp.max_vel[CalibrationParam::forward]*rot;
00550             target = (wp.leg[i].neutral + vfp*b*dir);
00551           } else {
00552             target = (wp.leg[i].neutral + vfp*b*dir).rotate_z(vfa*b);
00553           }
00554           target.z+=wp.sag;
00555           liftPos[i]=legpos[i];
00556           downPos[i]=target;
00557           legw[i].airpath.create(legpos[i],target,wp.leg[i].lift_vel,wp.leg[i].down_vel);
00558         }else{
00559           legpos[i].z = wp.leg[i].neutral.z;
00560         }
00561         legw[i].air = air;
00562       }
00563       
00564       if(air){
00565         legw[i].cyc = (float)( (cycle - lift_time) / air_f );
00566         legpos[i] = legw[i].airpath.eval(legw[i].cyc);
00567         
00568         // Core tss "SmoothWalk" addition follows
00569         // KLUDGY MOD. Goal: reduce the height of the
00570         // AIBO's steps as its velocity nears zero.
00571         // Since I don't know how most of this code 
00572         // works, I'll directly alter legpos[i].z in
00573         // the following code to change the z height
00574         // with velocity.
00575         double velfraction_x = fabs(vel_xya.x / MAX_DX);
00576         double velfraction_y = fabs(vel_xya.y / MAX_DY);
00577         double velfraction_a = fabs(vel_xya.z / MAX_DA * 2); //rotation seems more sensitive
00578         
00579         // Choose the biggest velfraction
00580         double velfraction =
00581         (velfraction_x > velfraction_y) ?
00582         velfraction_x : velfraction_y;
00583         if(velfraction_a > velfraction)
00584           velfraction = velfraction_a;
00585         
00586         // Modify legpos[i].z with velfraction to
00587         // shrink it down
00588         //velfraction = atan(velfraction * M_PI);
00589         
00590         velfraction-=1;
00591         velfraction*=velfraction;
00592         velfraction*=velfraction;
00593         
00594         legpos[i].z *= 1-velfraction;
00595         // Core tss "SmoothWalk" addition ends
00596       }else{
00597         if(dir==0)
00598           legpos[i]=wp.leg[i].neutral;
00599         else {
00600           if(wp.useDiffDrive) {
00601             tm = wp.period/1000.f * 0.75f; //wtf is the 0.75 based on?  Don't ask me, i just work here! (ejt)
00602             double vfa;
00603             if(step_count<0 && (acc_style==CALIBRATION_ACCEL || (acc_style==DEFAULT_ACCEL && !config->motion.inf_walk_accel))) {
00604               vfa   = bound(cal_target_vel_xya.z, vel_xya.z-max_accel_xya.z*tm, vel_xya.z+max_accel_xya.z*tm);
00605             } else {
00606               vfa   = cal_target_vel_xya.z;
00607             }
00608             legpos[i] -= delta.loc*dir;
00609             float rot = (float)( vfa/cp.max_vel[CalibrationParam::rotate]*TimeStep * slowmo / 1000 );
00610             if((i&1)==0)
00611               rot=-rot;
00612             legpos[i].x -= cp.max_vel[CalibrationParam::forward]*rot;
00613           } else {
00614             legpos[i] = (legpos[i] - delta.loc*dir).rotate_z(-delta.angle.z);
00615           }
00616         }
00617       }
00618       
00619       GetLegAngles(nextlegangles,legpos[i],nextpos,i);
00620       for(unsigned int j=0; j<JointsPerLeg; j++)
00621         cmds[LegOffset+i*JointsPerLeg+j][frame].set((float)nextlegangles[j]);
00622       
00623     }
00624     last_cycle=cycle;
00625   }
00626   
00627   for(unsigned int joint=LegOffset; joint<LegOffset+NumLegJoints; joint++)
00628     motman->setOutput(this,joint,cmds[joint]);
00629   
00630 #ifndef PLATFORM_APERIOS
00631   if(contactChanged) {
00632     DriverMessaging::FixedPoints contactMsg;
00633     for(unsigned int leg=0; leg<NumLegs; ++leg) {  //need to add all contacts to sync which are current
00634 #ifdef TGT_IS_AIBO
00635       // not entirely accurate to place contact at (0,0,0):
00636       // there's a heel around it that will roll forward with step, but we'll just fix the point below the heel
00637       fmat::Column<3> off = kine->baseToLink(FootFrameOffset+leg).rotation() * fmat::pack(0,0,-BallOfFootRadius);
00638       if(!legw[leg].air)
00639         contactMsg.addEntry(FootFrameOffset+leg, off);
00640 #else
00641       if(!legw[leg].air)
00642         contactMsg.addEntry(FootFrameOffset+leg, 0,0,0);
00643 #endif
00644     }
00645     DriverMessaging::postMessage(contactMsg);
00646   }
00647 #endif
00648     
00649   //    cout << "WalkMC-done" << endl;
00650   return NumLegs*JointsPerLeg;
00651   
00652 #elif defined(TGT_HAS_WHEELS)
00653   // see if we've reached our target displacement
00654   unsigned int t = getTravelTime();
00655   double adjustedTravelSeconds = t/1000.0;
00656   // std::cout << "tvelx= " << target_vel_xya.x << "  travtime=" << t << "  dispx=" << target_disp_xya.x << std::endl;
00657   if (step_count > 0)  // use nsteps=-1 to move forever
00658     if ( fabs(target_vel_xya.x)*adjustedTravelSeconds > fabs(target_disp_xya.x) ||
00659       fabs(target_vel_xya.z)*adjustedTravelSeconds > fabs(target_disp_xya.z) ) {
00660       target_vel_xya.set(0,0,0);
00661       last_target_vel_xya=target_vel_xya;
00662       LocomotionEvent e(EventBase::locomotionEGID,getID(),EventBase::statusETID,t);
00663       e.setXYA((float)target_vel_xya.x,(float)target_vel_xya.y,(float)target_vel_xya.z);
00664       postEvent(e);
00665       postEvent(EventBase(EventBase::motmanEGID,getID(),EventBase::statusETID,getTravelTime()));
00666       return 0;
00667     }
00668   
00669   // we're not at target yet, so recompute wheel velocities
00670   vel_xya=target_vel_xya;
00671 #ifdef TGT_IS_CREATE
00672   /* this used to be a config item, now hardcoded due to deprecation
00673     * of this section (only place it was used, should be extracted from kinematics) */
00674   const float WHEEL_BASE_WIDTH = 265;
00675 #else
00676   const float WHEEL_BASE_WIDTH = 140;
00677 #endif
00678   float turnvel = (float)vel_xya.z * WHEEL_BASE_WIDTH/2;
00679   if ( fabs(turnvel) < 1e-3)  // eliminate oscillations that generate lots of LocomotionEvents
00680     turnvel = 0;
00681   float left = (float)vel_xya.x - turnvel;
00682   float right = (float)vel_xya.x + turnvel;
00683   /* debugging stuff
00684   static int myCounter = 0;
00685   if ( (myCounter++ % 25) == 0 || vel_xya.x != target_vel_xya.x )
00686     std::cout << "update: " << vel_xya.x << ' ' << vel_xya.y << ' ' << vel_xya.z << " -> " << left << ' ' << right
00687               << " last xvel: " << vel_xya.x << " target xvel: " << target_vel_xya.x
00688               << ": id=" << getID() << " prio=" << motman->getPriority(getID()) << " cnt=" << myCounter << std::endl;
00689   */
00690   for(unsigned int frame=0; frame<NumFrames; frame++) {
00691     cmds[LWheelOffset][frame]=left;
00692     cmds[RWheelOffset][frame]=right;
00693   }
00694   motman->setOutput(this, LWheelOffset, cmds[LWheelOffset]);
00695   motman->setOutput(this, RWheelOffset, cmds[RWheelOffset]);
00696   return NumWheels;
00697   
00698 #else
00699   return 0;
00700 #endif
00701 }
00702 
00703 void CMPackWalkMC::resetLegPos() {
00704   BodyPosition nextpos;
00705   nextpos.loc.set(0,0,wp.body_height);
00706   nextpos.angle.set(0,wp.body_angle,0);
00707 #ifdef TGT_HAS_LEGS
00708   for(unsigned int i=0; i<NumLegs; i++) {
00709     double tmp[JointsPerLeg];
00710     for(unsigned int j=0; j<JointsPerLeg; j++)
00711       tmp[j]=state->outputs[LegOffset+i*JointsPerLeg+j];
00712     GetLegPosition(legpos[i],tmp,nextpos,i);
00713     /*
00714      for(unsigned int j=0; j<JointsPerLeg; j++)
00715      cout << state->outputs[LegOffset+i*JointsPerLeg+j] << ' ';
00716      cout << "  ->  " << legpos[i].x << ' ' << legpos[i].y << ' ' << legpos[i].z << endl;
00717      */
00718   }
00719 #endif
00720   //cout << "----------------------" << endl;
00721 }
00722 
00723 unsigned int checksum(const char *data,int num)
00724 {
00725   unsigned long c;
00726   int i;
00727   
00728   c = 0;
00729   for(i=0; i<num; i++){
00730     c = c ^ (data[i]*13 + 37);
00731     c = (c << 13) | (c >> 19);
00732   }
00733   
00734   return(c);
00735 }
00736 
00737 void CMPackWalkMC::applyCalibration(const float mat[3][11], const vector3d& in, vector3d& out) {
00738   float inmat[11];
00739   inmat[0]=(float)in.x;
00740   inmat[1]=(float)in.y;
00741   inmat[2]=(float)in.z;
00742   inmat[3]=std::abs((float)in.y);
00743   inmat[4]=std::abs((float)in.z);
00744   inmat[5]=std::exp(-.5f*(float)in.z*(float)in.z)*std::sin((float)in.z*2.5f);
00745   inmat[6]=(float)in.x*(float)in.x+(float)in.y*(float)in.y;
00746   inmat[7]=(float)in.x*(float)in.z;
00747   inmat[8]=(float)in.y*(float)in.x;
00748   inmat[9]=(float)in.z*(float)in.y;
00749   inmat[10]=1;
00750   out.set(0,0,0);
00751   for(unsigned int c=0; c<11; c++)
00752     out.x+=mat[0][c]*inmat[c];
00753   for(unsigned int c=0; c<11; c++)
00754     out.y+=mat[1][c]*inmat[c];
00755   for(unsigned int c=0; c<11; c++)
00756     out.z+=mat[2][c]*inmat[c];
00757 }
00758 
00759 /*! @file
00760  * @brief Implements CMPackWalkMC, a MotionCommand for walking around
00761  * @author CMU RoboSoccer 2001-2002 (Creator)
00762  * @author ejt (ported)
00763  *
00764  * @verbinclude CMPack_license.txt
00765  */
00766 

Tekkotsu v5.1CVS
Generated Fri Mar 16 05:26:35 2012 by Doxygen 1.6.3