00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 #ifndef KMLMOTBASE_H
00014 #define KMLMOTBASE_H
00015 
00016 #include "common/exception.h"
00017 #include "common/dllexport.h"
00018 
00019 #include "KNI/kmlCommon.h"
00020 #include "KNI/cplBase.h"
00021 
00022 #include <vector>
00023 
00024 class CKatBase; 
00025 class CMotBase; 
00026 
00027 
00028 
00029 
00030 
00031 
00034 struct  TMotDesc {
00035         byte            slvID;          
00036 };
00037 
00040 struct  TKatMOT {
00041         short           cnt;            
00042         CMotBase*       arr;            
00043         TMotDesc*       desc;           
00044 };
00045 
00048 enum TMotCmdFlg {
00049         MCF_OFF                 = 0,            
00050         MCF_CALIB               = 4,            
00051         MCF_FREEZE              = 8,            
00052         MCF_ON                  = 24,           
00053         MCF_CLEAR_MOVEBUFFER    = 32            
00054 };
00055 
00058 enum TMotStsFlg {
00059         MSF_MECHSTOP    = 1,            
00060         MSF_MAXPOS      = 2,            
00061         MSF_MINPOS      = 4,            
00062         MSF_DESPOS      = 8,            
00063         MSF_NORMOPSTAT  = 16,           
00064         MSF_MOTCRASHED  = 40,           
00065         MSF_NLINMOV     = 88,           
00066         MSF_LINMOV      = 152,          
00067         MSF_NOTVALID    = 128           
00068 };
00069 enum TSearchDir {                       
00070         DIR_POSITIVE,
00071         DIR_NEGATIVE
00072 };
00073 
00074 
00075 
00076 
00079 struct TMotGNL {
00080         CKatBase*       own;            
00081         byte            SID;            
00082 };
00083 
00086 struct TMotSFW {
00087         byte            version;        
00088         byte            subversion;     
00089         byte            revision;       
00090         byte            type;           
00091         byte            subtype;        
00092 };
00093 
00096 struct TMotAPS {
00097         TMotCmdFlg      mcfAPS;         
00098         short           actpos;         
00099 };
00100 
00103 struct TMotTPS {
00104         TMotCmdFlg      mcfTPS;         
00105         short           tarpos;         
00106 };
00107 
00110 struct TMotSCP {
00111 
00112         
00113         
00114         byte            maxppwm;        
00115         byte            maxnpwm;        
00116         byte            kP;             
00117         byte            kI;             
00118         byte            kD;             
00119         byte            kARW;           
00120         
00121         byte            kP_speed;       
00122         byte            kI_speed;       
00123         byte            kD_speed;       
00124 
00125         
00126         
00127         byte            maxppwm_nmp;    
00128         byte            maxnpwm_nmp;    
00129         byte            kspeed_nmp;     
00130         byte            kpos_nmp;       
00131         byte            kI_nmp;         
00132         int             crash_limit_nmp;        
00133         int             crash_limit_lin_nmp;    
00134 };
00135 
00138 struct TMotDYL {
00139 
00140         
00141         
00142         byte            maxaccel;       
00143         byte            maxdecel;       
00144         short           minpos;         
00145         short           maxpspeed;      
00146         short           maxnspeed;      
00147         
00148         
00149         byte            maxcurr;        
00150         byte            actcurr;        
00151 
00152         
00153         
00154         byte            maxaccel_nmp;   
00155         short           maxpspeed_nmp;  
00156         short           maxnspeed_nmp;  
00157         byte            maxcurr_nmp;    
00158 };
00159 
00162 struct TMotPVP {
00163         TMotStsFlg      msf;            
00164         short           pos;            
00165         short           vel;            
00166         byte            pwm;            
00167 };
00168 
00171 struct TMotENL {
00172         int     enc_range;              
00173         int     enc_minpos;             
00174         int     enc_maxpos;             
00175         int     enc_per_cycle;          
00176         int     enc_tolerance;          
00177 };
00178 
00179 
00182 struct TMotCLB {
00183   bool          enable;                 
00184   short       order;                    
00185   
00186   TSearchDir    dir;                    
00187   TMotCmdFlg    mcf;                    
00188   
00189   int                 encoderPositionAfter;
00190   bool          isCalibrated;
00191   
00192   TMotDYL dyl;
00193   TMotSCP scp;
00194 };
00195 
00196 
00199 struct TMotInit {
00200         int             encoderOffset;
00201         int             encodersPerCycle;
00202         double          angleOffset;
00203         double          angleRange;
00204         int             rotationDirection;
00205 
00206         
00207         double                  angleStop;
00208 };
00209 
00210 
00211 
00220 class DLLDIR CMotBase {
00221 
00222         friend class CKatBase;
00223 
00224 
00225 protected:
00226         TMotGNL gnl;                    
00227         TMotAPS aps;                    
00228         TMotTPS tps;                    
00229         TMotSCP scp;                    
00230         TMotDYL dyl;                    
00231         TMotPVP pvp;                    
00232         TMotSFW sfw;                    
00233         TMotCLB  _calibrationParameters;
00234         TMotENL  _encoderLimits;        
00235         TMotInit _initialParameters;
00236         bool    freedom;                
00237         bool    blocked;                
00238 
00239 
00240 public:
00241         const TMotGNL* GetGNL() { return &gnl; }
00242         const TMotAPS* GetAPS() { return &aps; }
00243         const TMotTPS* GetTPS() { return &tps; }
00244         const TMotSCP* GetSCP() { return &scp; }
00245         const TMotDYL* GetDYL() { return &dyl; }
00246         const TMotPVP* GetPVP() { return &pvp; }
00247         const TMotSFW* GetSFW() { return &sfw; }
00248         const TMotCLB* GetCLB() { return &_calibrationParameters; }
00249 
00250         const TMotInit* GetInitialParameters() { return &_initialParameters; }
00251         int GetEncoderTolerance() { return _encoderLimits.enc_tolerance; }
00252         int GetEncoderMinPos() { return _encoderLimits.enc_minpos; }    
00253         int GetEncoderMaxPos() { return _encoderLimits.enc_maxpos; }    
00254         int GetEncoderRange() { return _encoderLimits.enc_range; }      
00255 bool GetFreedom() { return freedom; }bool GetBlocked() { return blocked; }
00260 
00261 protected:
00262         CCplBase* protocol;     
00263 
00264 public:
00265         virtual ~CMotBase() {}  
00266 
00267         bool init(CKatBase* _own, const TMotDesc _motDesc, CCplBase* protocol);
00268         void sendAPS(const TMotAPS* _aps);      void sendTPS(const TMotTPS* _tps);
00273         void recvPVP(); void recvSFW();
00278 
00279         void setSCP(TMotSCP _scp) { scp = _scp; }
00280         void setDYL(TMotDYL _dyl) { dyl = _dyl; }
00281 
00282         
00283         void setInitialParameters(double angleOffset, double angleRange, int encodersPerCycle, int encoderOffset, int rotationDirection);
00284         void setCalibrationParameters(bool doCalibration, short order, TSearchDir direction, TMotCmdFlg motorFlagAfter, int encoderPositionAfter);
00285         void setCalibrated(bool calibrated);
00286                                       
00287         void setTolerance(int tolerance);
00288 
00291         bool checkAngleInRange(double angle);   
00292         bool checkEncoderInRange(int encoder);
00293 
00296         void inc(int dif, bool wait = false, int tolerance = 100, long timeout = TM_ENDLESS);
00299         void dec(int dif, bool wait = false, int tolerance = 100, long timeout = TM_ENDLESS);
00302         void mov(int tar, bool wait = false, int tolerance = 100, long timeout = TM_ENDLESS);
00303 
00306         void waitForMotor(int tar, int encTolerance = 100, short mode = 0, int waitTimeout = TM_ENDLESS);
00307 
00310         void incDegrees(double dif, bool wait = false, int tolerance = 100, long timeout = TM_ENDLESS);
00313         void decDegrees(double dif, bool wait = false, int tolerance = 100, long timeout = TM_ENDLESS);
00316         void movDegrees(double tar, bool wait = false, int tolerance = 100, long timeout = TM_ENDLESS);
00317 
00320         void resetBlocked();
00321 
00322 
00326     void sendSpline(short targetPosition, short duration, short p1, short p2, short p3, short p4);
00327 
00330         void setSpeedLimits(short positiveVelocity, short negativeVelocity);
00331         void setSpeedLimit(short velocity) { setSpeedLimits(velocity, velocity); }
00332 
00335         void setAccelerationLimit( short acceleration );
00336         
00339         void setPwmLimits(byte maxppwm, byte maxnpwm);
00340         
00343         void setControllerParameters(byte kSpeed, byte kPos, byte kI);
00344         
00347         void setCrashLimit(int limit);
00349         void setCrashLimitLinear(int limit_lin);
00351         void setSpeedCollisionLimit(int limit);
00353         void setPositionCollisionLimit(int limit);
00354 
00361         void getParameterOrLimit(int subcommand, byte* R1, byte* R2, byte* R3);
00362 };
00363 
00364 
00365 #endif