robot

Dependencies:   FastPWM3 mbed

main.cpp

Committer:
bwang
Date:
2016-10-30
Revision:
16:f283d6032fe5
Parent:
15:b583cd30b063
Child:
17:2b852039bb05

File content as of revision 16:f283d6032fe5:

#include "mbed.h"
#include "math.h"
#include "PositionSensor.h"
#include "FastPWM.h"
#include "config_motor.h"
#include "config_loop.h"
#include "config_inverter.h"
#include "pwm_in.h"

FastPWM *a;
FastPWM *b;
FastPWM *c;
DigitalOut en(EN);
PwmIn throttle(TH_PIN, 1100, 1900);
PositionSensorEncoder pos(CPR, 0);

Serial pc(USBTX, USBRX);

int adval1, adval2;
float ia, ib, ic, alpha, beta, d, q, vd, vq, p;
float p_mech, last_p_mech, w;

float ia_supp_offset = 0.0f, ib_supp_offset = 0.0f; //current sensor offset due to bias resistor inaccuracies, etc (mV)

float d_integral = 0.0f, q_integral = 0.0f;
float last_d = 0.0f, last_q = 0.0f;
float d_ref = 0.0f, q_ref = 0.0f;

bool control_enabled = false;

void commutate();
void zero_current();
void config_globals();
void startup_msg();

void go_enabled();
void go_disabled();
float fminf(float, float);
float fmaxf(float, float);

extern "C" void TIM1_UP_TIM10_IRQHandler(void) {
    if (TIM1->SR & TIM_SR_UIF ) {
        ADC1->CR2  |= 0x40000000; 
        volatile int delay;
        for (delay = 0; delay < 35; delay++);
        adval1 = ADC1->DR;
        adval2 = ADC2->DR;
        commutate();
    }
    TIM1->SR = 0x00;
}

void zero_current(){
    for (int i = 0; i < 1000; i++){
        ia_supp_offset += (float) (ADC1->DR);
        ib_supp_offset += (float) (ADC2->DR);
        ADC1->CR2  |= 0x40000000;
        wait_us(100); 
    }
    ia_supp_offset /= 1000.0f;
    ib_supp_offset /= 1000.0f;
    ia_supp_offset = ia_supp_offset / 4096.0f * AVDD - I_OFFSET;
    ib_supp_offset = ib_supp_offset / 4096.0f * AVDD - I_OFFSET;
}

void config_globals() {
    pc.baud(115200);
    
    //Enable clocks for GPIOs
    RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN;
    RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN;
    RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN;
    
    RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; //enable TIM1 clock
    
    a = new FastPWM(PWMA);
    b = new FastPWM(PWMB);
    c = new FastPWM(PWMC);
    
    NVIC_EnableIRQ(TIM1_UP_TIM10_IRQn); //Enable TIM1 IRQ

    TIM1->DIER |= TIM_DIER_UIE; //enable update interrupt
    TIM1->CR1 = 0x40; //CMS = 10, interrupt only when counting up
    TIM1->CR1 |= TIM_CR1_ARPE; //autoreload on, 
    TIM1->RCR |= 0x01; //update event once per up/down count of tim1 
    TIM1->EGR |= TIM_EGR_UG;
    
    TIM1->PSC = 0x00; //no prescaler, timer counts up in sync with the peripheral clock
    TIM1->ARR = 0x4650; //5 Khz
    TIM1->CCER |= ~(TIM_CCER_CC1NP); //Interupt when low side is on.
    TIM1->CR1 |= TIM_CR1_CEN;
    
    //ADC Setup
    RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; // clock for ADC1
    RCC->APB2ENR |= RCC_APB2ENR_ADC2EN; // clock for ADC2
    
    ADC->CCR = 0x00000006; //Regular simultaneous mode, 3 channels
    
    ADC1->CR2 |= ADC_CR2_ADON; //ADC1 on
    ADC1->SQR3 = 0x0000004; //PA_4 as ADC1, sequence 0
    
    ADC2->CR2 |= ADC_CR2_ADON; //ADC2 ON
    ADC2->SQR3 = 0x00000008; //PB_0 as ADC2, sequence 1
    
    GPIOA->MODER |= (1 << 8);
    GPIOA->MODER |= (1 << 9);
    
    GPIOA->MODER |= (1 << 2);
    GPIOA->MODER |= (1 << 3);
    
    GPIOA->MODER |= (1 << 0);
    GPIOA->MODER |= (1 << 1);
    
    GPIOB->MODER |= (1 << 0);
    GPIOB->MODER |= (1 << 1);
    
    GPIOC->MODER |= (1 << 2);
    GPIOC->MODER |= (1 << 3);
    
    //DAC setup
    RCC->APB1ENR |= 0x20000000;
    DAC->CR |= DAC_CR_EN2;
    
    GPIOA->MODER |= (1 << 10);
    GPIOA->MODER |= (1 << 11);
    
    //Zero duty cycles
    set_dtc(a, 0.0f);
    set_dtc(b, 0.0f);
    set_dtc(c, 0.0f);
    
    wait_ms(250);
    zero_current();
    p_mech = pos.GetMechPosition();
    en = 1;
}

void startup_msg() {
    pc.printf("%s\n\r\n\r", "FOC'ed in the Bot Rev A.");
    pc.printf("%s\n\r", "====Config Data====");
    pc.printf("Current Sensor Offset: %f mV\n\r", I_OFFSET);
    pc.printf("Current Sensor Scale: %f mv/A\n\r", I_SCALE);
    pc.printf("Bus Voltage: %f V\n\r", BUS_VOLTAGE);
    pc.printf("Pole pairs: %d\n\r", (int) POLE_PAIRS);
    pc.printf("Resolver lobes: %d\n\r", (int) RESOLVER_LOBES);
    pc.printf("Loop KP: %f\n\r", KP);
    pc.printf("Loop KI: %f\n\r", KI);
    pc.printf("Ia offset: %f mV\n\r", ia_supp_offset);
    pc.printf("Ib offset: %f mV\n\r", ib_supp_offset);
    pc.printf("\n\r");
}    

void commutate() {
    if(control_enabled && !throttle.get_enabled()) go_disabled();
    if(!control_enabled && throttle.get_enabled()) go_enabled();
    
    p = pos.GetElecPosition() - POS_OFFSET;
    if (p < 0) p += 2 * PI;
    
    last_p_mech = p_mech;
    p_mech = pos.GetMechPosition();
    float dp_mech = p_mech - last_p_mech;
    if (dp_mech < 0.0f) dp_mech += 2 * PI;
    if (dp_mech > 2 * PI) dp_mech -= 2 * PI;
    float loop_period = (float) (TIM1->ARR) / 90.0f;
    float w_raw = dp_mech * (float) 1e6 / loop_period; //rad/s
    w = W_FILTER_STRENGTH * w + (1.0f - W_FILTER_STRENGTH) * w_raw;
    
    q_ref = throttle.get_throttle() * Q_MAX;
    d_ref = 0.0f;
    
    float sin_p = sinf(p);
    float cos_p = cosf(p);
    
    //float pos_dac = 0.85f * p / (2 * PI) + 0.05f; //uncomment me to write position to the DAC
    //DAC->DHR12R2 = (unsigned int) (pos_dac * 4096);
    
    ia = ((float) adval1 / 4096.0f * AVDD - I_OFFSET - ia_supp_offset) / I_SCALE;
    ib = ((float) adval2 / 4096.0f * AVDD - I_OFFSET - ib_supp_offset) / I_SCALE;
    ic = -ia - ib;
    
    float u = CURRENT_U;
    float v = CURRENT_V;
    
    alpha = u;
    beta = 1 / sqrtf(3.0f) * u + 2 / sqrtf(3.0f) * v;
    
    d = alpha * cos_p - beta * sin_p;
    q = -alpha * sin_p - beta * cos_p;
    
    float d_err = d_ref - d;
    float q_err = q_ref - q;
    
    d_integral += d_err * KI;
    q_integral += q_err * KI;
    
    if (q_integral > INTEGRAL_MAX) q_integral = INTEGRAL_MAX;
    if (d_integral > INTEGRAL_MAX) d_integral = INTEGRAL_MAX;
    if (q_integral < -INTEGRAL_MAX) q_integral = -INTEGRAL_MAX;
    if (d_integral < -INTEGRAL_MAX) d_integral = -INTEGRAL_MAX;
    
    if(control_enabled) {
        vd = KP * d_err + d_integral;
        vq = KP * q_err + q_integral;
    } else {
        vd = 0;
        vq = 0;
    }
    
    if (vd < -1.0f) vd = -1.0f;
    if (vd > 1.0f) vd = 1.0f;
    if (vq < -1.0f) vq = -1.0f;
    if (vq > 1.0f) vq = 1.0f;
    
    //DAC->DHR12R2 = (unsigned int) (-q * 20 + 2048); //uncomment me to write I_q to the DAC
    //DAC->DHR12R2 = (unsigned int) (-vd * 2000 + 2048);
    
    //vd = 0.0f; //uncomment me for voltage mode testing
    //vq = 1.0f;
    
    float valpha = vd * cos_p - vq * sin_p;
    float vbeta = vd * sin_p + vq * cos_p;
    
    float va = valpha;
    float vb = -0.5f * valpha - sqrtf(3) / 2.0f * vbeta;
    float vc = -0.5f * valpha + sqrtf(3) / 2.0f * vbeta;
    
    float voff = (fminf(va, fminf(vb, vc)) + fmaxf(va, fmaxf(vb, vc)))/2.0f;
    va = va - voff;
    vb = vb - voff;
    vc = vc - voff;
    
    set_dtc(a, 0.5f + 0.5f * va);
    set_dtc(b, 0.5f + 0.5f * vb);
    set_dtc(c, 0.5f + 0.5f * vc);
}
    
int main() {
    config_globals();
    startup_msg();
    
    for (;;) {
        //pc.printf("%f\n\r", p);
        //wait(0.1);
    }
}

void go_enabled() {
    d_integral = 0.0f;
    q_integral = 0.0f;
    control_enabled = true;
    en = 1;
}

void go_disabled() {
    control_enabled = false;
    en = 0;
}

float fminf(float a, float b) {
    if(a < b) return a;
    return b;
}

float fmaxf(float a, float b) {
    if(a > b) return a;
    return b;
}