Library for driving a motor with one PWM and one DIR signal using PI control.

Fork of Motor2 by Reiko Randoja

motor.cpp

Committer:
Reiko
Date:
2013-09-14
Revision:
2:3faf5dcde08f
Parent:
1:c97f8bcd6c0f
Child:
3:94db629c0a83

File content as of revision 2:3faf5dcde08f:

#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 = 2.0;
    iMulti = 0.01;
    dMulti = 1;
    error = 0.0;
    prevError = 0.0;
    P = 0.0;
    I = 0.0;
    minPwm = 0.1;
    
    currentSpeed = 0;
}

void Motor::setPWM(float newPWM) {
    if (newPWM < 0) {
        pwm = -1 * newPWM;
        extIO->setPin(dir1);
        extIO->clearPin(dir2);
    } else {
        pwm = 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() {
    /*int setPoint = 0;
    float pMulti = 0.1;
    float iMulti = 0.001;
    int error = 0;
    int prevError = 0;
    float P = 0.0;
    float I = 0.0;*/
    
    prevError = error;
    error = (float)(setPoint - getDecoderCount()) / 250.0;
    
    //float err = (float)error / 250.0;
    float minPwmValue = minPwm;
    
    if (setPoint == 0) {
        minPwmValue = 0.0;
    } else if (setPoint < 0) {
        minPwmValue = -minPwm;
    }
    
    I += error * iMulti;
    //constrain integral
    if (I < -1.0) I = -1.0;
    if (I > 1.0) I = 1.0;
    
    //D = error - prevError;
    
    //float newPWMvalue = minPwmValue + error * pMulti + I + dMulti * D;
    float newPWMvalue = minPwmValue + error * pMulti + I;

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

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