Bayley Wang
/
foc-ed_in_the_bot_compact
robot
main.cpp@23:c77d4b42de17, 2016-11-05 (annotated)
- Committer:
- bwang
- Date:
- Sat Nov 05 11:10:37 2016 +0000
- Revision:
- 23:c77d4b42de17
- Parent:
- 22:72840d3db788
- Child:
- 24:5e18a87a0e95
last working commit before scrambling transforms
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
bwang | 0:bac9c3a3a6ca | 1 | #include "mbed.h" |
bwang | 0:bac9c3a3a6ca | 2 | #include "math.h" |
bwang | 19:a6cf15f89f3d | 3 | |
bwang | 0:bac9c3a3a6ca | 4 | #include "PositionSensor.h" |
bwang | 0:bac9c3a3a6ca | 5 | #include "FastPWM.h" |
bwang | 18:3863ca45cf26 | 6 | #include "PwmIn.h" |
bwang | 19:a6cf15f89f3d | 7 | #include "MathHelpers.h" |
bwang | 18:3863ca45cf26 | 8 | |
bwang | 15:b583cd30b063 | 9 | #include "config_motor.h" |
bwang | 15:b583cd30b063 | 10 | #include "config_loop.h" |
bwang | 19:a6cf15f89f3d | 11 | #include "config_pins.h" |
bwang | 15:b583cd30b063 | 12 | #include "config_inverter.h" |
bwang | 0:bac9c3a3a6ca | 13 | |
bwang | 1:7b61790f6be9 | 14 | FastPWM *a; |
bwang | 1:7b61790f6be9 | 15 | FastPWM *b; |
bwang | 1:7b61790f6be9 | 16 | FastPWM *c; |
bwang | 0:bac9c3a3a6ca | 17 | DigitalOut en(EN); |
bwang | 18:3863ca45cf26 | 18 | PwmIn throttle_in(TH_PIN, 1100, 1900); |
bwang | 0:bac9c3a3a6ca | 19 | PositionSensorEncoder pos(CPR, 0); |
bwang | 0:bac9c3a3a6ca | 20 | |
bwang | 0:bac9c3a3a6ca | 21 | Serial pc(USBTX, USBRX); |
bwang | 0:bac9c3a3a6ca | 22 | |
bwang | 1:7b61790f6be9 | 23 | int adval1, adval2; |
bwang | 2:eabe8feaaabb | 24 | float ia, ib, ic, alpha, beta, d, q, vd, vq, p; |
bwang | 15:b583cd30b063 | 25 | float p_mech, last_p_mech, w; |
bwang | 22:72840d3db788 | 26 | float d_filtered = 0.0f, q_filtered = 0.0f; |
bwang | 2:eabe8feaaabb | 27 | |
bwang | 1:7b61790f6be9 | 28 | float ia_supp_offset = 0.0f, ib_supp_offset = 0.0f; //current sensor offset due to bias resistor inaccuracies, etc (mV) |
bwang | 1:7b61790f6be9 | 29 | |
bwang | 2:eabe8feaaabb | 30 | float d_integral = 0.0f, q_integral = 0.0f; |
bwang | 2:eabe8feaaabb | 31 | float last_d = 0.0f, last_q = 0.0f; |
bwang | 14:59c4fcc1a4f7 | 32 | float d_ref = 0.0f, q_ref = 0.0f; |
bwang | 2:eabe8feaaabb | 33 | |
bwang | 16:f283d6032fe5 | 34 | bool control_enabled = false; |
dicarloj | 13:41d102a53caf | 35 | |
bwang | 4:a6669248ce4d | 36 | void commutate(); |
bwang | 3:9b20da3f0055 | 37 | void zero_current(); |
bwang | 3:9b20da3f0055 | 38 | void config_globals(); |
bwang | 3:9b20da3f0055 | 39 | void startup_msg(); |
bwang | 2:eabe8feaaabb | 40 | |
bwang | 16:f283d6032fe5 | 41 | void go_enabled(); |
bwang | 16:f283d6032fe5 | 42 | void go_disabled(); |
dicarloj | 13:41d102a53caf | 43 | |
bwang | 1:7b61790f6be9 | 44 | extern "C" void TIM1_UP_TIM10_IRQHandler(void) { |
bwang | 1:7b61790f6be9 | 45 | if (TIM1->SR & TIM_SR_UIF ) { |
bwang | 4:a6669248ce4d | 46 | ADC1->CR2 |= 0x40000000; |
bwang | 4:a6669248ce4d | 47 | volatile int delay; |
bwang | 4:a6669248ce4d | 48 | for (delay = 0; delay < 35; delay++); |
bwang | 1:7b61790f6be9 | 49 | adval1 = ADC1->DR; |
bwang | 1:7b61790f6be9 | 50 | adval2 = ADC2->DR; |
bwang | 4:a6669248ce4d | 51 | commutate(); |
bwang | 1:7b61790f6be9 | 52 | } |
bwang | 1:7b61790f6be9 | 53 | TIM1->SR = 0x00; |
bwang | 1:7b61790f6be9 | 54 | } |
bwang | 1:7b61790f6be9 | 55 | |
bwang | 1:7b61790f6be9 | 56 | void zero_current(){ |
bwang | 1:7b61790f6be9 | 57 | for (int i = 0; i < 1000; i++){ |
bwang | 1:7b61790f6be9 | 58 | ia_supp_offset += (float) (ADC1->DR); |
bwang | 1:7b61790f6be9 | 59 | ib_supp_offset += (float) (ADC2->DR); |
bwang | 1:7b61790f6be9 | 60 | ADC1->CR2 |= 0x40000000; |
bwang | 1:7b61790f6be9 | 61 | wait_us(100); |
bwang | 1:7b61790f6be9 | 62 | } |
bwang | 1:7b61790f6be9 | 63 | ia_supp_offset /= 1000.0f; |
bwang | 1:7b61790f6be9 | 64 | ib_supp_offset /= 1000.0f; |
bwang | 1:7b61790f6be9 | 65 | ia_supp_offset = ia_supp_offset / 4096.0f * AVDD - I_OFFSET; |
bwang | 1:7b61790f6be9 | 66 | ib_supp_offset = ib_supp_offset / 4096.0f * AVDD - I_OFFSET; |
bwang | 1:7b61790f6be9 | 67 | } |
bwang | 0:bac9c3a3a6ca | 68 | |
bwang | 17:2b852039bb05 | 69 | void update_velocity() { |
bwang | 15:b583cd30b063 | 70 | last_p_mech = p_mech; |
bwang | 15:b583cd30b063 | 71 | p_mech = pos.GetMechPosition(); |
bwang | 15:b583cd30b063 | 72 | float dp_mech = p_mech - last_p_mech; |
bwang | 19:a6cf15f89f3d | 73 | if (dp_mech < -PI) dp_mech += 2 * PI; |
bwang | 19:a6cf15f89f3d | 74 | if (dp_mech > PI) dp_mech -= 2 * PI; |
bwang | 15:b583cd30b063 | 75 | float loop_period = (float) (TIM1->ARR) / 90.0f; |
bwang | 15:b583cd30b063 | 76 | float w_raw = dp_mech * (float) 1e6 / loop_period; //rad/s |
bwang | 15:b583cd30b063 | 77 | w = W_FILTER_STRENGTH * w + (1.0f - W_FILTER_STRENGTH) * w_raw; |
bwang | 18:3863ca45cf26 | 78 | } |
bwang | 18:3863ca45cf26 | 79 | |
bwang | 18:3863ca45cf26 | 80 | float get_torque_cmd(float throttle, float w) { |
bwang | 19:a6cf15f89f3d | 81 | return throttle * FORWARD_TORQUE_MAX; |
bwang | 18:3863ca45cf26 | 82 | } |
bwang | 18:3863ca45cf26 | 83 | |
bwang | 18:3863ca45cf26 | 84 | //fill in d, q ref based on torque cmd and current velocity |
bwang | 18:3863ca45cf26 | 85 | void get_dq(float torque, float w, float *d, float *q) { |
bwang | 18:3863ca45cf26 | 86 | *d = 0.0f; |
bwang | 22:72840d3db788 | 87 | *q = Q_MAX;//torque / KT < Q_MAX ? torque / KT : Q_MAX; |
bwang | 18:3863ca45cf26 | 88 | } |
bwang | 17:2b852039bb05 | 89 | |
bwang | 17:2b852039bb05 | 90 | void commutate() { |
bwang | 18:3863ca45cf26 | 91 | if(control_enabled && !throttle_in.get_enabled()) go_disabled(); |
bwang | 18:3863ca45cf26 | 92 | if(!control_enabled && throttle_in.get_enabled()) go_enabled(); |
bwang | 17:2b852039bb05 | 93 | |
bwang | 17:2b852039bb05 | 94 | update_velocity(); |
bwang | 17:2b852039bb05 | 95 | |
bwang | 17:2b852039bb05 | 96 | p = pos.GetElecPosition() - POS_OFFSET; |
bwang | 17:2b852039bb05 | 97 | if (p < 0) p += 2 * PI; |
bwang | 15:b583cd30b063 | 98 | |
bwang | 18:3863ca45cf26 | 99 | float torque = get_torque_cmd(throttle_in.get_throttle(), w); |
bwang | 19:a6cf15f89f3d | 100 | get_dq(torque, w, &d_ref, &q_ref); |
bwang | 16:f283d6032fe5 | 101 | |
bwang | 2:eabe8feaaabb | 102 | float sin_p = sinf(p); |
bwang | 2:eabe8feaaabb | 103 | float cos_p = cosf(p); |
bwang | 2:eabe8feaaabb | 104 | |
bwang | 1:7b61790f6be9 | 105 | ia = ((float) adval1 / 4096.0f * AVDD - I_OFFSET - ia_supp_offset) / I_SCALE; |
bwang | 1:7b61790f6be9 | 106 | ib = ((float) adval2 / 4096.0f * AVDD - I_OFFSET - ib_supp_offset) / I_SCALE; |
bwang | 2:eabe8feaaabb | 107 | ic = -ia - ib; |
bwang | 0:bac9c3a3a6ca | 108 | |
bwang | 10:f49df0fe0382 | 109 | float u = CURRENT_U; |
bwang | 10:f49df0fe0382 | 110 | float v = CURRENT_V; |
bwang | 2:eabe8feaaabb | 111 | |
bwang | 2:eabe8feaaabb | 112 | alpha = u; |
bwang | 2:eabe8feaaabb | 113 | beta = 1 / sqrtf(3.0f) * u + 2 / sqrtf(3.0f) * v; |
bwang | 2:eabe8feaaabb | 114 | |
bwang | 2:eabe8feaaabb | 115 | d = alpha * cos_p - beta * sin_p; |
bwang | 2:eabe8feaaabb | 116 | q = -alpha * sin_p - beta * cos_p; |
bwang | 2:eabe8feaaabb | 117 | |
bwang | 22:72840d3db788 | 118 | d_filtered = DQ_FILTER_STRENGTH * d_filtered + (1.0f - DQ_FILTER_STRENGTH) * d; |
bwang | 22:72840d3db788 | 119 | q_filtered = DQ_FILTER_STRENGTH * q_filtered + (1.0f - DQ_FILTER_STRENGTH) * q; |
bwang | 22:72840d3db788 | 120 | |
bwang | 22:72840d3db788 | 121 | float d_err = d_ref - d_filtered; |
bwang | 22:72840d3db788 | 122 | float q_err = q_ref - q_filtered; |
bwang | 2:eabe8feaaabb | 123 | |
bwang | 2:eabe8feaaabb | 124 | d_integral += d_err * KI; |
bwang | 2:eabe8feaaabb | 125 | q_integral += q_err * KI; |
bwang | 2:eabe8feaaabb | 126 | |
bwang | 20:91ae97a811e3 | 127 | q_integral = constrain(q_integral, -INTEGRAL_MAX, INTEGRAL_MAX); |
bwang | 20:91ae97a811e3 | 128 | d_integral = constrain(d_integral, -INTEGRAL_MAX, INTEGRAL_MAX); |
bwang | 2:eabe8feaaabb | 129 | |
bwang | 21:b7fb355c8c2d | 130 | if(control_enabled) { |
bwang | 21:b7fb355c8c2d | 131 | vd = KP * d_err + d_integral; |
bwang | 21:b7fb355c8c2d | 132 | vq = KP * q_err + q_integral; |
bwang | 21:b7fb355c8c2d | 133 | } else { |
bwang | 21:b7fb355c8c2d | 134 | vd = 0; |
bwang | 21:b7fb355c8c2d | 135 | vq = 0; |
bwang | 21:b7fb355c8c2d | 136 | } |
bwang | 21:b7fb355c8c2d | 137 | |
bwang | 20:91ae97a811e3 | 138 | vd = constrain(vd, -1.0f, 1.0f); |
bwang | 20:91ae97a811e3 | 139 | vq = constrain(vq, -1.0f, 1.0f); |
bwang | 4:a6669248ce4d | 140 | |
bwang | 2:eabe8feaaabb | 141 | float valpha = vd * cos_p - vq * sin_p; |
bwang | 2:eabe8feaaabb | 142 | float vbeta = vd * sin_p + vq * cos_p; |
bwang | 2:eabe8feaaabb | 143 | |
bwang | 2:eabe8feaaabb | 144 | float va = valpha; |
bwang | 2:eabe8feaaabb | 145 | float vb = -0.5f * valpha - sqrtf(3) / 2.0f * vbeta; |
bwang | 2:eabe8feaaabb | 146 | float vc = -0.5f * valpha + sqrtf(3) / 2.0f * vbeta; |
bwang | 2:eabe8feaaabb | 147 | |
dicarloj | 13:41d102a53caf | 148 | float voff = (fminf(va, fminf(vb, vc)) + fmaxf(va, fmaxf(vb, vc)))/2.0f; |
dicarloj | 13:41d102a53caf | 149 | va = va - voff; |
dicarloj | 13:41d102a53caf | 150 | vb = vb - voff; |
dicarloj | 13:41d102a53caf | 151 | vc = vc - voff; |
dicarloj | 13:41d102a53caf | 152 | |
bwang | 2:eabe8feaaabb | 153 | set_dtc(a, 0.5f + 0.5f * va); |
bwang | 2:eabe8feaaabb | 154 | set_dtc(b, 0.5f + 0.5f * vb); |
bwang | 2:eabe8feaaabb | 155 | set_dtc(c, 0.5f + 0.5f * vc); |
bwang | 0:bac9c3a3a6ca | 156 | } |
bwang | 0:bac9c3a3a6ca | 157 | |
bwang | 0:bac9c3a3a6ca | 158 | int main() { |
bwang | 0:bac9c3a3a6ca | 159 | config_globals(); |
bwang | 0:bac9c3a3a6ca | 160 | startup_msg(); |
bwang | 0:bac9c3a3a6ca | 161 | |
bwang | 0:bac9c3a3a6ca | 162 | for (;;) { |
bwang | 0:bac9c3a3a6ca | 163 | } |
bwang | 0:bac9c3a3a6ca | 164 | } |
bwang | 16:f283d6032fe5 | 165 | |
bwang | 16:f283d6032fe5 | 166 | void go_enabled() { |
bwang | 16:f283d6032fe5 | 167 | d_integral = 0.0f; |
bwang | 16:f283d6032fe5 | 168 | q_integral = 0.0f; |
bwang | 16:f283d6032fe5 | 169 | control_enabled = true; |
bwang | 16:f283d6032fe5 | 170 | en = 1; |
bwang | 16:f283d6032fe5 | 171 | } |
bwang | 16:f283d6032fe5 | 172 | |
bwang | 16:f283d6032fe5 | 173 | void go_disabled() { |
bwang | 16:f283d6032fe5 | 174 | control_enabled = false; |
bwang | 16:f283d6032fe5 | 175 | en = 0; |
bwang | 16:f283d6032fe5 | 176 | } |
bwang | 16:f283d6032fe5 | 177 | |
bwang | 17:2b852039bb05 | 178 | void startup_msg() { |
bwang | 17:2b852039bb05 | 179 | pc.printf("%s\n\r\n\r", "FOC'ed in the Bot Rev A."); |
bwang | 17:2b852039bb05 | 180 | pc.printf("%s\n\r", "====Config Data===="); |
bwang | 17:2b852039bb05 | 181 | pc.printf("Current Sensor Offset: %f mV\n\r", I_OFFSET); |
bwang | 17:2b852039bb05 | 182 | pc.printf("Current Sensor Scale: %f mv/A\n\r", I_SCALE); |
bwang | 17:2b852039bb05 | 183 | pc.printf("Bus Voltage: %f V\n\r", BUS_VOLTAGE); |
bwang | 23:c77d4b42de17 | 184 | pc.printf("Switching Frequency: %f KHz \n\r", F_SW / 1000.0f); |
bwang | 17:2b852039bb05 | 185 | pc.printf("Pole pairs: %d\n\r", (int) POLE_PAIRS); |
bwang | 17:2b852039bb05 | 186 | pc.printf("Resolver lobes: %d\n\r", (int) RESOLVER_LOBES); |
bwang | 17:2b852039bb05 | 187 | pc.printf("Loop KP: %f\n\r", KP); |
bwang | 17:2b852039bb05 | 188 | pc.printf("Loop KI: %f\n\r", KI); |
bwang | 17:2b852039bb05 | 189 | pc.printf("Ia offset: %f mV\n\r", ia_supp_offset); |
bwang | 17:2b852039bb05 | 190 | pc.printf("Ib offset: %f mV\n\r", ib_supp_offset); |
bwang | 17:2b852039bb05 | 191 | pc.printf("\n\r"); |
bwang | 17:2b852039bb05 | 192 | } |
bwang | 17:2b852039bb05 | 193 | |
bwang | 17:2b852039bb05 | 194 | void config_globals() { |
bwang | 17:2b852039bb05 | 195 | pc.baud(115200); |
bwang | 17:2b852039bb05 | 196 | |
bwang | 17:2b852039bb05 | 197 | //Enable clocks for GPIOs |
bwang | 17:2b852039bb05 | 198 | RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; |
bwang | 17:2b852039bb05 | 199 | RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN; |
bwang | 17:2b852039bb05 | 200 | RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN; |
bwang | 17:2b852039bb05 | 201 | |
bwang | 17:2b852039bb05 | 202 | RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; //enable TIM1 clock |
bwang | 17:2b852039bb05 | 203 | |
bwang | 17:2b852039bb05 | 204 | a = new FastPWM(PWMA); |
bwang | 17:2b852039bb05 | 205 | b = new FastPWM(PWMB); |
bwang | 17:2b852039bb05 | 206 | c = new FastPWM(PWMC); |
bwang | 17:2b852039bb05 | 207 | |
bwang | 17:2b852039bb05 | 208 | NVIC_EnableIRQ(TIM1_UP_TIM10_IRQn); //Enable TIM1 IRQ |
bwang | 17:2b852039bb05 | 209 | |
bwang | 17:2b852039bb05 | 210 | TIM1->DIER |= TIM_DIER_UIE; //enable update interrupt |
bwang | 17:2b852039bb05 | 211 | TIM1->CR1 = 0x40; //CMS = 10, interrupt only when counting up |
bwang | 17:2b852039bb05 | 212 | TIM1->CR1 |= TIM_CR1_ARPE; //autoreload on, |
bwang | 17:2b852039bb05 | 213 | TIM1->RCR |= 0x01; //update event once per up/down count of tim1 |
bwang | 17:2b852039bb05 | 214 | TIM1->EGR |= TIM_EGR_UG; |
bwang | 17:2b852039bb05 | 215 | |
bwang | 17:2b852039bb05 | 216 | TIM1->PSC = 0x00; //no prescaler, timer counts up in sync with the peripheral clock |
bwang | 22:72840d3db788 | 217 | TIM1->ARR = (int) ((float) 9e7 / F_SW); |
bwang | 17:2b852039bb05 | 218 | TIM1->CCER |= ~(TIM_CCER_CC1NP); //Interupt when low side is on. |
bwang | 17:2b852039bb05 | 219 | TIM1->CR1 |= TIM_CR1_CEN; |
bwang | 17:2b852039bb05 | 220 | |
bwang | 17:2b852039bb05 | 221 | //ADC Setup |
bwang | 17:2b852039bb05 | 222 | RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; // clock for ADC1 |
bwang | 17:2b852039bb05 | 223 | RCC->APB2ENR |= RCC_APB2ENR_ADC2EN; // clock for ADC2 |
bwang | 17:2b852039bb05 | 224 | |
bwang | 17:2b852039bb05 | 225 | ADC->CCR = 0x00000006; //Regular simultaneous mode, 3 channels |
bwang | 17:2b852039bb05 | 226 | |
bwang | 17:2b852039bb05 | 227 | ADC1->CR2 |= ADC_CR2_ADON; //ADC1 on |
bwang | 17:2b852039bb05 | 228 | ADC1->SQR3 = 0x0000004; //PA_4 as ADC1, sequence 0 |
bwang | 17:2b852039bb05 | 229 | |
bwang | 17:2b852039bb05 | 230 | ADC2->CR2 |= ADC_CR2_ADON; //ADC2 ON |
bwang | 17:2b852039bb05 | 231 | ADC2->SQR3 = 0x00000008; //PB_0 as ADC2, sequence 1 |
bwang | 17:2b852039bb05 | 232 | |
bwang | 17:2b852039bb05 | 233 | GPIOA->MODER |= (1 << 8); |
bwang | 17:2b852039bb05 | 234 | GPIOA->MODER |= (1 << 9); |
bwang | 17:2b852039bb05 | 235 | |
bwang | 17:2b852039bb05 | 236 | GPIOA->MODER |= (1 << 2); |
bwang | 17:2b852039bb05 | 237 | GPIOA->MODER |= (1 << 3); |
bwang | 17:2b852039bb05 | 238 | |
bwang | 17:2b852039bb05 | 239 | GPIOA->MODER |= (1 << 0); |
bwang | 17:2b852039bb05 | 240 | GPIOA->MODER |= (1 << 1); |
bwang | 17:2b852039bb05 | 241 | |
bwang | 17:2b852039bb05 | 242 | GPIOB->MODER |= (1 << 0); |
bwang | 17:2b852039bb05 | 243 | GPIOB->MODER |= (1 << 1); |
bwang | 17:2b852039bb05 | 244 | |
bwang | 17:2b852039bb05 | 245 | GPIOC->MODER |= (1 << 2); |
bwang | 17:2b852039bb05 | 246 | GPIOC->MODER |= (1 << 3); |
bwang | 17:2b852039bb05 | 247 | |
bwang | 17:2b852039bb05 | 248 | //DAC setup |
bwang | 17:2b852039bb05 | 249 | RCC->APB1ENR |= 0x20000000; |
bwang | 17:2b852039bb05 | 250 | DAC->CR |= DAC_CR_EN2; |
bwang | 17:2b852039bb05 | 251 | |
bwang | 17:2b852039bb05 | 252 | GPIOA->MODER |= (1 << 10); |
bwang | 17:2b852039bb05 | 253 | GPIOA->MODER |= (1 << 11); |
bwang | 17:2b852039bb05 | 254 | |
bwang | 17:2b852039bb05 | 255 | //Zero duty cycles |
bwang | 17:2b852039bb05 | 256 | set_dtc(a, 0.0f); |
bwang | 17:2b852039bb05 | 257 | set_dtc(b, 0.0f); |
bwang | 17:2b852039bb05 | 258 | set_dtc(c, 0.0f); |
bwang | 17:2b852039bb05 | 259 | |
bwang | 17:2b852039bb05 | 260 | wait_ms(250); |
bwang | 17:2b852039bb05 | 261 | zero_current(); |
bwang | 17:2b852039bb05 | 262 | p_mech = pos.GetMechPosition(); |
bwang | 17:2b852039bb05 | 263 | en = 1; |
bwang | 17:2b852039bb05 | 264 | } |