|
| 1 | +/* |
| 2 | + Feedback 360 Angle Control [Low Level Example].c |
| 3 | + |
| 4 | + This is a simplified example of how the low-level position control is done. |
| 5 | + These features would normally be tucked away in a library like abdrive360 |
| 6 | + or servo360 with functions to request measured angle, set target angle, |
| 7 | + and etc. |
| 8 | +*/ |
| 9 | + |
| 10 | +// Library inlcudes |
| 11 | +#include "simpletools.h" // For pulse_in, print, scan etc... |
| 12 | +#include "servo.h" // For servo pulse control |
| 13 | + |
| 14 | +int pinFeedback = 14; // P14 connected to feedback line |
| 15 | +int pinControl = 12; // P12 connected to control line |
| 16 | + |
| 17 | +volatile int angle, targetAngle; // Global shared variables |
| 18 | +volatile int Kp = 1; // Proportional constant |
| 19 | + |
| 20 | +void feedback360(); // Position monitoring |
| 21 | +void control360(); // Position control |
| 22 | + |
| 23 | +int main() // Main function |
| 24 | +{ |
| 25 | + cog_run(feedback360, 128); // Run feedback360 in a cog |
| 26 | + cog_run(control360, 128); // Run control360 in a cog |
| 27 | + pause(100); // Wait 1/10 s, might not need |
| 28 | + |
| 29 | + while(1) // Main loop |
| 30 | + { |
| 31 | + print("Enter angle: "); // Prompt user for angle |
| 32 | + scan("%d", &targetAngle); // Get entered angle |
| 33 | + print("\r"); // Next line |
| 34 | + while(abs(targetAngle - angle) > 4) // Display until close to finish |
| 35 | + { |
| 36 | + print("targetAngle = %d, angle = %d\r", // Display target & measured |
| 37 | + targetAngle, angle); |
| 38 | + pause(50); // ...every 50 ms |
| 39 | + } |
| 40 | + } |
| 41 | +} |
| 42 | + |
| 43 | + |
| 44 | +void feedback360() // Cog keeps angle variable updated |
| 45 | +{ |
| 46 | + int unitsFC = 360; // Units in a full circle |
| 47 | + int dutyScale = 1000; // Scale duty cycle to 1/1000ths |
| 48 | + int dcMin = 29; // Minimum duty cycle |
| 49 | + int dcMax = 971; // Maximum duty cycle |
| 50 | + int q2min = unitsFC/4; // For checking if in 1st quadrant |
| 51 | + int q3max = q2min * 3; // For checking if in 4th quadrant |
| 52 | + int turns = 0; // For tracking turns |
| 53 | + // dc is duty cycle, theta is 0 to 359 angle, thetaP is theta from previous |
| 54 | + // loop repetition, tHigh and tLow are the high and low signal times for |
| 55 | + // duty cycle calculations. |
| 56 | + int dc, theta, thetaP, tHigh, tLow; |
| 57 | + |
| 58 | + // Measure feedback signal high/low times. |
| 59 | + tLow = pulse_in(pinFeedback, 0); // Measure low time |
| 60 | + tHigh = pulse_in(pinFeedback, 1); // Measure high time |
| 61 | + |
| 62 | + // Calcualte initial duty cycle and angle. |
| 63 | + dc = (dutyScale * tHigh) / (tHigh + tLow); |
| 64 | + theta = (unitsFC - 1) - ((dc - dcMin) * unitsFC) / (dcMax - dcMin + 1); |
| 65 | + thetaP = theta; |
| 66 | + |
| 67 | + while(1) // Main loop for this cog |
| 68 | + { |
| 69 | + // Measure high and low times, making sure to only take valid cycle |
| 70 | + // times (a high and a low on opposite sides of the 0/359 boundary |
| 71 | + // will not be valid. |
| 72 | + int tCycle = 0; // Clear cycle time |
| 73 | + while(1) // Keep checking |
| 74 | + { |
| 75 | + tHigh = pulse_in(pinFeedback, 1); // Measure time high |
| 76 | + tLow = pulse_in(pinFeedback, 0); // Measure time low |
| 77 | + tCycle = tHigh + tLow; |
| 78 | + if((tCycle > 1000) && (tCycle < 1200)) // If cycle time valid |
| 79 | + break; // break from loop |
| 80 | + } |
| 81 | + dc = (dutyScale * tHigh) / tCycle; // Calculate duty cycle |
| 82 | + |
| 83 | + // This gives a theta increasing int the |
| 84 | + // counterclockwise direction. |
| 85 | + theta = (unitsFC - 1) - // Calculate angle |
| 86 | + ((dc - dcMin) * unitsFC) |
| 87 | + / (dcMax - dcMin + 1); |
| 88 | + |
| 89 | + if(theta < 0) // Keep theta valid |
| 90 | + theta = 0; |
| 91 | + else if(theta > (unitsFC - 1)) |
| 92 | + theta = unitsFC - 1; |
| 93 | + |
| 94 | + // If transition from quadrant 4 to |
| 95 | + // quadrant 1, increase turns count. |
| 96 | + if((theta < q2min) && (thetaP > q3max)) |
| 97 | + turns++; |
| 98 | + // If transition from quadrant 1 to |
| 99 | + // quadrant 4, decrease turns count. |
| 100 | + else if((thetaP < q2min) && (theta > q3max)) |
| 101 | + turns --; |
| 102 | + |
| 103 | + // Construct the angle measurement from the turns count and |
| 104 | + // current theta value. |
| 105 | + if(turns >= 0) |
| 106 | + angle = (turns * unitsFC) + theta; |
| 107 | + else if(turns < 0) |
| 108 | + angle = ((turns + 1) * unitsFC) - (unitsFC - theta); |
| 109 | + |
| 110 | + thetaP = theta; // Theta previous for next rep |
| 111 | + } |
| 112 | +} |
| 113 | + |
| 114 | + |
| 115 | +// Most rudimentary control system example, |
| 116 | +// just proportional. This could be done |
| 117 | +// in the same cog as the angle mesurement. |
| 118 | +void control360() // Cog for control system |
| 119 | +{ |
| 120 | + servo_speed(pinControl, 0); // Start servo control cog |
| 121 | + |
| 122 | + int errorAngle, output, offset; // Control system variables |
| 123 | + |
| 124 | + while(1) // Main loop for this cog |
| 125 | + { |
| 126 | + errorAngle = targetAngle - angle; // Calculate error |
| 127 | + output = errorAngle * Kp; // Calculate proportional |
| 128 | + if(output > 200) output = 200; // Clamp output |
| 129 | + if(output < -200) output = -200; |
| 130 | + if(errorAngle > 0) // Add offset |
| 131 | + offset = 30; |
| 132 | + else if(errorAngle < 0) |
| 133 | + offset = -30; |
| 134 | + else |
| 135 | + offset = 0; |
| 136 | + servo_speed(pinControl, output + offset); // Set output |
| 137 | + pause(20); // Repeat after 20 ms |
| 138 | + } |
| 139 | +} |
| 140 | + |
| 141 | + |
0 commit comments