Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
main.cpp@11:043a63c952a0, 2017-03-14 (annotated)
- Committer:
- dkp14
- Date:
- Tue Mar 14 21:50:17 2017 +0000
- Revision:
- 11:043a63c952a0
- Parent:
- 10:25d8696cb2c6
- Child:
- 13:deb1e793f125
- Child:
- 16:d4948633c559
velocity/time measurements done
Who changed what in which revision?
| User | Revision | Line number | New contents of line |
|---|---|---|---|
| dkp14 | 0:74a5723d604a | 1 | #include "mbed.h" |
| dkp14 | 0:74a5723d604a | 2 | #include "rtos.h" |
| dkp14 | 0:74a5723d604a | 3 | #include "definitions.h" |
| dkp14 | 0:74a5723d604a | 4 | #include "motorControl.h" |
| dkp14 | 0:74a5723d604a | 5 | |
| dkp14 | 10:25d8696cb2c6 | 6 | #define kp 0.75f |
| dkp14 | 10:25d8696cb2c6 | 7 | #define ki 0.5f |
| dkp14 | 10:25d8696cb2c6 | 8 | #define kd 1.0f |
| dkp14 | 10:25d8696cb2c6 | 9 | #define dt 0.02f //given in ms, used to call a ticker |
| dkp14 | 4:dc705df93090 | 10 | |
| dkp14 | 0:74a5723d604a | 11 | volatile uint8_t state = 0; |
| dkp14 | 11:043a63c952a0 | 12 | //volatile uint8_t orState = 0; //Motor rotor offset. |
| dkp14 | 11:043a63c952a0 | 13 | volatile float w3 = 0; //Angular velocity |
| dkp14 | 11:043a63c952a0 | 14 | volatile float duty = 0.40; |
| dkp14 | 4:dc705df93090 | 15 | volatile int count_i3 = 0; |
| dkp14 | 10:25d8696cb2c6 | 16 | const float angularVelocities[17] = {0, 112.355598, 164.975998, 218.721725, |
| dkp14 | 10:25d8696cb2c6 | 17 | 260.672943, 291.491364, 308.479126, 316.805908, 321.183929, 324.010712, |
| dkp14 | 10:25d8696cb2c6 | 18 | 326.146759, 336.187103, 351.175629, 364.887604, 377.856659, 387.58432, |
| dkp14 | 10:25d8696cb2c6 | 19 | 392.540314}; |
| dkp14 | 11:043a63c952a0 | 20 | const float dutyCycles [17] = {0, 0.28, 0.33, 0.38, 0.42, 0.47, 0.52, 0.57, |
| dkp14 | 11:043a63c952a0 | 21 | 0.63, 0.68, 0.73, 0.78, 0.83, 0.88, 0.93, 0.98, 1}; |
| dkp14 | 0:74a5723d604a | 22 | |
| dkp14 | 10:25d8696cb2c6 | 23 | const float angle = 6.283; //2*pi for 1 revolution |
| dkp14 | 0:74a5723d604a | 24 | Timer dt_I3; |
| dkp14 | 0:74a5723d604a | 25 | Timer motorTimer; |
| dkp14 | 4:dc705df93090 | 26 | Ticker controlTicker; |
| dkp14 | 4:dc705df93090 | 27 | |
| dkp14 | 4:dc705df93090 | 28 | volatile float fi0 = 0; //number of revs done |
| dkp14 | 11:043a63c952a0 | 29 | volatile int goalRevs = 50; |
| dkp14 | 4:dc705df93090 | 30 | volatile float fi = 2*3.1415*goalRevs; |
| dkp14 | 4:dc705df93090 | 31 | volatile float goalW = 0; //desired angular velocity |
| dkp14 | 10:25d8696cb2c6 | 32 | volatile float accError = 0; |
| dkp14 | 10:25d8696cb2c6 | 33 | volatile float prevError = 0; |
| dkp14 | 4:dc705df93090 | 34 | |
| dkp14 | 11:043a63c952a0 | 35 | float getDuty(float w){ |
| dkp14 | 11:043a63c952a0 | 36 | for (int i=0;i<16;i++) { //iterate through the angular velocities |
| dkp14 | 11:043a63c952a0 | 37 | if (w > angularVelocities[i] && w <= angularVelocities[i+1]) { |
| dkp14 | 11:043a63c952a0 | 38 | if (w-angularVelocities[i] < angularVelocities[i+1]-w ) { |
| dkp14 | 11:043a63c952a0 | 39 | return dutyCycles[i]; |
| dkp14 | 11:043a63c952a0 | 40 | } |
| dkp14 | 11:043a63c952a0 | 41 | else { |
| dkp14 | 11:043a63c952a0 | 42 | return dutyCycles[i+1]; |
| dkp14 | 11:043a63c952a0 | 43 | } |
| dkp14 | 11:043a63c952a0 | 44 | } |
| dkp14 | 11:043a63c952a0 | 45 | } |
| dkp14 | 11:043a63c952a0 | 46 | return 0; |
| dkp14 | 11:043a63c952a0 | 47 | } |
| dkp14 | 11:043a63c952a0 | 48 | |
| dkp14 | 4:dc705df93090 | 49 | void control(){ |
| dkp14 | 4:dc705df93090 | 50 | fi0 = 6.283 * count_i3; //fi0 = 2*pi*revs |
| dkp14 | 10:25d8696cb2c6 | 51 | float error = fi - fi0; |
| dkp14 | 10:25d8696cb2c6 | 52 | accError += error*dt; |
| dkp14 | 10:25d8696cb2c6 | 53 | float dError = (prevError - error)/dt; |
| dkp14 | 4:dc705df93090 | 54 | goalW = kp*error + ki*accError + kd*dError; |
| dkp14 | 10:25d8696cb2c6 | 55 | prevError = error; |
| dkp14 | 11:043a63c952a0 | 56 | duty = getDuty(goalW); |
| dkp14 | 0:74a5723d604a | 57 | } |
| dkp14 | 0:74a5723d604a | 58 | |
| dkp14 | 0:74a5723d604a | 59 | void i3rise(){ |
| dkp14 | 0:74a5723d604a | 60 | state = updateState(); |
| davidanderle | 2:fe637a5f3387 | 61 | motorOut((state-orState+lead+6)%6, duty); |
| dkp14 | 0:74a5723d604a | 62 | |
| dkp14 | 11:043a63c952a0 | 63 | w3 = angle/dt_I3.read(); //Calc angular velocity |
| dkp14 | 0:74a5723d604a | 64 | |
| dkp14 | 0:74a5723d604a | 65 | dt_I3.reset(); |
| dkp14 | 4:dc705df93090 | 66 | count_i3++; |
| dkp14 | 0:74a5723d604a | 67 | } |
| dkp14 | 0:74a5723d604a | 68 | |
| dkp14 | 11:043a63c952a0 | 69 | void i_edge(){ |
| dkp14 | 0:74a5723d604a | 70 | state = updateState(); |
| davidanderle | 2:fe637a5f3387 | 71 | motorOut((state-orState+lead+6)%6, duty); |
| dkp14 | 0:74a5723d604a | 72 | } |
| dkp14 | 0:74a5723d604a | 73 | |
| dkp14 | 0:74a5723d604a | 74 | void CHA_rise(){ |
| dkp14 | 0:74a5723d604a | 75 | } |
| dkp14 | 0:74a5723d604a | 76 | void CHA_fall(){ |
| dkp14 | 0:74a5723d604a | 77 | } |
| dkp14 | 0:74a5723d604a | 78 | void CHB_rise(){ |
| dkp14 | 0:74a5723d604a | 79 | } |
| dkp14 | 0:74a5723d604a | 80 | void CHB_fall(){ |
| dkp14 | 0:74a5723d604a | 81 | } |
| dkp14 | 0:74a5723d604a | 82 | |
| dkp14 | 0:74a5723d604a | 83 | int main() { |
| dkp14 | 11:043a63c952a0 | 84 | motorHome(); //Initialise motor before any interrupt |
| dkp14 | 0:74a5723d604a | 85 | |
| dkp14 | 11:043a63c952a0 | 86 | dt_I3.start(); //Start the time counters for velocity |
| dkp14 | 11:043a63c952a0 | 87 | |
| dkp14 | 11:043a63c952a0 | 88 | //controlTicker.attach(&control, dt); |
| dkp14 | 0:74a5723d604a | 89 | |
| dkp14 | 11:043a63c952a0 | 90 | I1.rise(&i_edge); //Assign interrupt handlers for LEDs |
| dkp14 | 11:043a63c952a0 | 91 | I1.fall(&i_edge); |
| dkp14 | 11:043a63c952a0 | 92 | I2.rise(&i_edge); |
| dkp14 | 11:043a63c952a0 | 93 | I2.fall(&i_edge); |
| dkp14 | 0:74a5723d604a | 94 | I3.rise(&i3rise); |
| dkp14 | 11:043a63c952a0 | 95 | I3.fall(&i_edge); |
| dkp14 | 0:74a5723d604a | 96 | // CHA.rise(&CHA_rise); |
| dkp14 | 0:74a5723d604a | 97 | // CHA.fall(&CHA_fall); |
| dkp14 | 0:74a5723d604a | 98 | // CHB.rise(&CHB_rise); |
| dkp14 | 0:74a5723d604a | 99 | // CHB.fall(&CHB_fall); |
| dkp14 | 11:043a63c952a0 | 100 | |
| dkp14 | 10:25d8696cb2c6 | 101 | state = updateState(); |
| dkp14 | 11:043a63c952a0 | 102 | motorTimer.start(); |
| dkp14 | 10:25d8696cb2c6 | 103 | motorOut((state-orState+lead+6)%6, 0.5f); //Kickstart the motor |
| dkp14 | 11:043a63c952a0 | 104 | wait(60); |
| dkp14 | 10:25d8696cb2c6 | 105 | |
| dkp14 | 11:043a63c952a0 | 106 | while (1/*count_i3<=goalRevs*/) { |
| dkp14 | 11:043a63c952a0 | 107 | pc.printf("Speed: %f, duty cycle: %f, revs done: %d \n\r",w3, duty, count_i3); |
| dkp14 | 11:043a63c952a0 | 108 | stopMotor(); |
| dkp14 | 11:043a63c952a0 | 109 | return 0; |
| dkp14 | 11:043a63c952a0 | 110 | /* |
| dkp14 | 11:043a63c952a0 | 111 | if(duty < 0.00f) { |
| dkp14 | 4:dc705df93090 | 112 | stopMotor(); |
| dkp14 | 10:25d8696cb2c6 | 113 | return 0; |
| dkp14 | 4:dc705df93090 | 114 | } |
| dkp14 | 11:043a63c952a0 | 115 | */ |
| dkp14 | 7:6bf4a61cf7c7 | 116 | /* |
| dkp14 | 10:25d8696cb2c6 | 117 | if(motorTimer.read() >= 30) { |
| dkp14 | 0:74a5723d604a | 118 | stopMotor(); |
| dkp14 | 0:74a5723d604a | 119 | return 0; |
| dkp14 | 0:74a5723d604a | 120 | } |
| dkp14 | 4:dc705df93090 | 121 | */ |
| dkp14 | 0:74a5723d604a | 122 | } |
| dkp14 | 0:74a5723d604a | 123 | } |
