Motor

Fork of Motor by Reiko Randoja

motor.cpp

Committer:
Reiko
Date:
2013-09-14
Revision:
3:94db629c0a83
Parent:
2:3faf5dcde08f
Child:
5:99fa6dffea40

File content as of revision 3:94db629c0a83:

#include "motor.h"

Motor::Motor(PinName PWMpin, PCA9555 *ioExt, unsigned int dir1Pin, unsigned int dir2Pin, PinName encA, PinName encB)
    : pwm(PWMpin), extIO(ioExt), dir1(dir1Pin), dir2(dir2Pin), qed(encA, encB) {
 
    PwmOut pwm(PWMpin);
    pwm.period_ms(1);
    setPoint = 0;
    pMulti = 4;
    iDiv = 8;
    dMulti = 1;
    error = 0;
    prevError = 0;
    P = 0;
    I = 0;
    minPwm = 100;
    pidMulti = 128;
    iMax = 256 * pidMulti;
    
    currentSpeed = 0;
}

void Motor::setPWM(int newPWM) {
    if (newPWM < 0) {
        pwm.pulsewidth_us(-1 * newPWM);
        //extIO->setPin(dir1);
        //extIO->clearPin(dir2);
    } else {
        pwm.pulsewidth_us(newPWM);
        //extIO->clearPin(dir1);
        //extIO->setPin(dir2);
    }    
}

int Motor::getSpeed() {
    return currentSpeed;
}

int Motor::getDecoderCount() {
    currentSpeed = qed.read();
    return currentSpeed;
}

void Motor::setSpeed(int newSpeed) {
    setPoint = newSpeed;
    if (newSpeed == 0) {
        resetPID();
    }
}

void Motor::pid() {    
    prevError = error;
    error = setPoint - getDecoderCount();
    
    //float err = (float)error / 250.0;
    float minPwmValue = minPwm;
    
    if (setPoint == 0) {
        minPwmValue = 0;
    } else if (setPoint < 0) {
        minPwmValue = -minPwm;
    }
    
    I += error * pidMulti / iDiv;
    //constrain integral
    if (I < -iMax) I = -iMax;
    if (I > iMax) I = iMax;
    
    //D = error - prevError;
    
    //float newPWMvalue = minPwmValue + error * pMulti + I + dMulti * D;
    int newPWMvalue = minPwmValue + error * pMulti + I / pidMulti;

    //constrain pwm
    if (newPWMvalue < -1000) newPWMvalue = -1000;
    if (newPWMvalue > 1000) newPWMvalue = 1000;
    
    setPWM(newPWMvalue);
}

void Motor::resetPID() {
    error = 0;
    prevError = 0;
    P = 0;
    I = 0;
    setPoint = 0;
    pwm = 0;
}