Nico van Duijn
/
AwkwardSegway
Robot that balances on two wheels
Fork of EpilepticSegway by
main.cpp@3:89e4ed1324bb, 2015-04-29 (annotated)
- Committer:
- nicovanduijn
- Date:
- Wed Apr 29 20:10:33 2015 +0000
- Revision:
- 3:89e4ed1324bb
- Parent:
- 2:89ada0b0b923
- Child:
- 4:51ea148fc592
all working! xbee, GUI, everything!
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
nicovanduijn | 0:4b50c71291e9 | 1 | /*//////////////////////////////////////////////////////////////// |
nicovanduijn | 0:4b50c71291e9 | 2 | ECE 4180 Final Project |
nicovanduijn | 0:4b50c71291e9 | 3 | Balancing Robot |
nicovanduijn | 0:4b50c71291e9 | 4 | |
nicovanduijn | 0:4b50c71291e9 | 5 | Nico van Duijn |
nicovanduijn | 0:4b50c71291e9 | 6 | Samer Mabrouk |
nicovanduijn | 0:4b50c71291e9 | 7 | Anthony Agnone |
nicovanduijn | 0:4b50c71291e9 | 8 | Jay Danner |
nicovanduijn | 0:4b50c71291e9 | 9 | 4/20/2015 |
nicovanduijn | 0:4b50c71291e9 | 10 | |
nicovanduijn | 0:4b50c71291e9 | 11 | This project consists of a robot balancing on two wheels. We use |
nicovanduijn | 0:4b50c71291e9 | 12 | the 9-axis IMU LSM9DS0 to give us Accelerometer and Gyroscope data |
nicovanduijn | 0:4b50c71291e9 | 13 | about the current angle and angular velocity of the robot. This |
nicovanduijn | 0:4b50c71291e9 | 14 | data is then filtered using complementary filters and PID control |
nicovanduijn | 0:4b50c71291e9 | 15 | to drive the two motors. The motors are controlled through digital |
nicovanduijn | 0:4b50c71291e9 | 16 | outputs in their direction and their seepd by PWM using an H-bridge. |
nicovanduijn | 0:4b50c71291e9 | 17 | The robot receives steering commands via the XBee module which is |
nicovanduijn | 0:4b50c71291e9 | 18 | interfaced with from a C# GUI that runs on a desktop computer. |
nicovanduijn | 0:4b50c71291e9 | 19 | |
nicovanduijn | 0:4b50c71291e9 | 20 | *///////////////////////////////////////////////////////////////// |
nicovanduijn | 0:4b50c71291e9 | 21 | |
nicovanduijn | 0:4b50c71291e9 | 22 | ////////////////////////////////////////////////////////////////// |
nicovanduijn | 0:4b50c71291e9 | 23 | // Includes |
nicovanduijn | 0:4b50c71291e9 | 24 | #include "mbed.h" // mbed library |
nicovanduijn | 0:4b50c71291e9 | 25 | #include "LSM9DS0.h" // 9axis IMU |
nicovanduijn | 0:4b50c71291e9 | 26 | #include "math.h" // We need to be able to do trig |
nicovanduijn | 0:4b50c71291e9 | 27 | |
nicovanduijn | 0:4b50c71291e9 | 28 | ////////////////////////////////////////////////////////////////// |
nicovanduijn | 0:4b50c71291e9 | 29 | // Constants |
nicovanduijn | 0:4b50c71291e9 | 30 | #define LSM9DS0_XM_ADDR 0x1D // Would be 0x1E if SDO_XM is LOW |
nicovanduijn | 0:4b50c71291e9 | 31 | #define LSM9DS0_G_ADDR 0x6B // Would be 0x6A if SDO_G is LOW |
nicovanduijn | 3:89e4ed1324bb | 32 | //#define DEBUG // Comment this out for final version |
nicovanduijn | 0:4b50c71291e9 | 33 | |
nicovanduijn | 0:4b50c71291e9 | 34 | ////////////////////////////////////////////////////////////////// |
nicovanduijn | 0:4b50c71291e9 | 35 | // I/O and object instatiation |
nicovanduijn | 0:4b50c71291e9 | 36 | PwmOut motorSpeedLeft(p21); // PWM port to control speed of left motor |
nicovanduijn | 0:4b50c71291e9 | 37 | PwmOut motorSpeedRight(p22); // PWM port to control speed of right motor |
nicovanduijn | 0:4b50c71291e9 | 38 | DigitalOut motorDirLeft(p24); // Digital pin for direction of left motor |
nicovanduijn | 0:4b50c71291e9 | 39 | DigitalOut NmotorDirLeft(p23); // Usually inverse of motorDirLeft |
nicovanduijn | 0:4b50c71291e9 | 40 | DigitalOut motorDirRight(p26); // Digital pin for direction of right motor |
nicovanduijn | 0:4b50c71291e9 | 41 | DigitalOut NmotorDirRight(p25); // Usually inverse of motorDirRight |
nicovanduijn | 0:4b50c71291e9 | 42 | LSM9DS0 imu(p9, p10, LSM9DS0_G_ADDR, LSM9DS0_XM_ADDR); // Creates on object for IMU |
nicovanduijn | 0:4b50c71291e9 | 43 | Ticker start; // Initialize ticker to call control function |
nicovanduijn | 3:89e4ed1324bb | 44 | Ticker GUI; // Ticker that calls the updateGUI |
nicovanduijn | 3:89e4ed1324bb | 45 | DigitalOut led1(LED1); // Use LED1 to provide some runtime info |
nicovanduijn | 3:89e4ed1324bb | 46 | Serial xbee(p13,p14); // Create serial port for Xbee |
nicovanduijn | 3:89e4ed1324bb | 47 | |
nicovanduijn | 3:89e4ed1324bb | 48 | typedef union _data { // Typedef so we can jump from chars to floats |
nicovanduijn | 2:89ada0b0b923 | 49 | float f; |
nicovanduijn | 2:89ada0b0b923 | 50 | char chars[4]; |
nicovanduijn | 3:89e4ed1324bb | 51 | int i; |
nicovanduijn | 2:89ada0b0b923 | 52 | } myData; |
nicovanduijn | 2:89ada0b0b923 | 53 | |
nicovanduijn | 0:4b50c71291e9 | 54 | ////////////////////////////////////////////////////////////////// |
nicovanduijn | 2:89ada0b0b923 | 55 | // Globals // double battery, lab floor: 67/100/600/160 cutoff ..35 |
nicovanduijn | 3:89e4ed1324bb | 56 | // positive turns |
nicovanduijn | 2:89ada0b0b923 | 57 | float kp = 59; //98 // 145 Proportional gain kU 400-500 |
nicovanduijn | 2:89ada0b0b923 | 58 | float kd = 105; //200 // Derivative gain |
nicovanduijn | 2:89ada0b0b923 | 59 | float ki = 670; //985 // Integrative gain |
nicovanduijn | 2:89ada0b0b923 | 60 | float OVERALL_SCALAR = 160; //160 // Overall scalar that speed is divided by |
nicovanduijn | 0:4b50c71291e9 | 61 | float accBias = 0; // Accelerometer Bias |
nicovanduijn | 0:4b50c71291e9 | 62 | float gyroBias = 0; // Gyro Bias |
nicovanduijn | 0:4b50c71291e9 | 63 | float accAngle = 0; // Global to hold angle measured by Accelerometer |
nicovanduijn | 0:4b50c71291e9 | 64 | float gyroAngle = 0; // This variable holds the amount the angle has changed |
nicovanduijn | 0:4b50c71291e9 | 65 | float speed = 0; // Variable for motor speed |
nicovanduijn | 0:4b50c71291e9 | 66 | float iAngle = 0; // Integral value of angle-error (sum of gyro-angles)NOT EQUAL TO gyroAngle |
nicovanduijn | 0:4b50c71291e9 | 67 | float dAngle = 0; // Derivative value for angle, angular velocity, how fast angle is changing |
nicovanduijn | 0:4b50c71291e9 | 68 | float pAngle = 0; // Proportional value for angle, current angle (best measurement) |
nicovanduijn | 0:4b50c71291e9 | 69 | float desiredAngle=0; // Setpoint. Set unequal zero to drive |
nicovanduijn | 3:89e4ed1324bb | 70 | float turnspeed=0; // Makes the robot turn |
nicovanduijn | 3:89e4ed1324bb | 71 | myData bytes; // Used to convert received/sent chars to ints and floats |
nicovanduijn | 3:89e4ed1324bb | 72 | |
nicovanduijn | 0:4b50c71291e9 | 73 | |
nicovanduijn | 0:4b50c71291e9 | 74 | ////////////////////////////////////////////////////////////////// |
nicovanduijn | 0:4b50c71291e9 | 75 | // Function Prototypes |
nicovanduijn | 0:4b50c71291e9 | 76 | void drive(float); // Function declaration for driving the motors |
nicovanduijn | 0:4b50c71291e9 | 77 | void calibrate(); // Function to calibrate gyro and accelerometer |
nicovanduijn | 0:4b50c71291e9 | 78 | void control(); // Function implementing PID control |
nicovanduijn | 2:89ada0b0b923 | 79 | void updateGUI(); |
nicovanduijn | 3:89e4ed1324bb | 80 | void checkValues(); |
nicovanduijn | 3:89e4ed1324bb | 81 | |
nicovanduijn | 0:4b50c71291e9 | 82 | ////////////////////////////////////////////////////////////////// |
nicovanduijn | 0:4b50c71291e9 | 83 | // Main function |
nicovanduijn | 0:4b50c71291e9 | 84 | int main() |
nicovanduijn | 0:4b50c71291e9 | 85 | { |
nicovanduijn | 3:89e4ed1324bb | 86 | led1=0; // Turn led off |
nicovanduijn | 0:4b50c71291e9 | 87 | uint16_t status = imu.begin(); // Use the begin() function to initialize the LSM9DS0 library. |
nicovanduijn | 3:89e4ed1324bb | 88 | xbee.baud(115200); // Baudrate. Pretty high, check if lower possible |
nicovanduijn | 0:4b50c71291e9 | 89 | calibrate(); // Calibrate gyro and accelerometer |
nicovanduijn | 0:4b50c71291e9 | 90 | start.attach(&control, 0.01); // Looptime 10ms ca. 100Hz |
nicovanduijn | 3:89e4ed1324bb | 91 | GUI.attach(&updateGUI, 0.5); // Update GUI twice a second |
nicovanduijn | 0:4b50c71291e9 | 92 | |
nicovanduijn | 3:89e4ed1324bb | 93 | while(1) { // Stay in this loop forever |
nicovanduijn | 3:89e4ed1324bb | 94 | led1=!led1; // Blink led1 to make sure the loop is running |
nicovanduijn | 3:89e4ed1324bb | 95 | wait_ms(500); // Looptime 500ms |
nicovanduijn | 0:4b50c71291e9 | 96 | } |
nicovanduijn | 0:4b50c71291e9 | 97 | } |
nicovanduijn | 0:4b50c71291e9 | 98 | |
nicovanduijn | 0:4b50c71291e9 | 99 | ///////////////////////////////////////////////////////////////// |
nicovanduijn | 0:4b50c71291e9 | 100 | // Control function, implements PID |
nicovanduijn | 0:4b50c71291e9 | 101 | void control() |
nicovanduijn | 0:4b50c71291e9 | 102 | { |
nicovanduijn | 0:4b50c71291e9 | 103 | dAngle=pAngle; // remember old p-value |
nicovanduijn | 0:4b50c71291e9 | 104 | imu.readGyro(); // Read the gyro |
nicovanduijn | 0:4b50c71291e9 | 105 | imu.readAccel(); // Read the Accelerometer |
nicovanduijn | 0:4b50c71291e9 | 106 | accAngle=(-1)*atan2(imu.ay,imu.az)*180/3.142-90-accBias; // Like this, 0 is upright, forward is negative, backward positive |
nicovanduijn | 0:4b50c71291e9 | 107 | gyroAngle=-(imu.gx-gyroBias)*0.01; // This is deltaangle, how much angle has changed |
nicovanduijn | 0:4b50c71291e9 | 108 | pAngle=0.98*(pAngle+gyroAngle)+0.02*accAngle-desiredAngle; // Complementary filter yields best value for current angle |
nicovanduijn | 0:4b50c71291e9 | 109 | dAngle=pAngle-dAngle; // Ang. Veloc. less noisy than dAngle = -(imu.gx-gyroBias); |
nicovanduijn | 0:4b50c71291e9 | 110 | iAngle+=(pAngle*.01); // integrate the angle (multiply by timestep to get dt!) |
nicovanduijn | 0:4b50c71291e9 | 111 | |
nicovanduijn | 2:89ada0b0b923 | 112 | if((abs(pAngle-desiredAngle)>=0.4)&&abs(pAngle-desiredAngle)<=15) { // If it is tilted enough, but not too much ||abs(imu.gx)>10 |
nicovanduijn | 0:4b50c71291e9 | 113 | speed=-(ki*iAngle+kd*dAngle+kp*pAngle)/OVERALL_SCALAR; // drive to correct |
nicovanduijn | 0:4b50c71291e9 | 114 | if(speed<-1) speed=-1; // Cap if undershoot |
nicovanduijn | 0:4b50c71291e9 | 115 | else if(speed>1) speed=1; // Cap if overshoot |
nicovanduijn | 0:4b50c71291e9 | 116 | } else speed=0; // If we've fallen over or are steady on top |
nicovanduijn | 0:4b50c71291e9 | 117 | drive(speed); // Write speed to the motors |
nicovanduijn | 3:89e4ed1324bb | 118 | checkValues(); // Checks if we need to update some values |
nicovanduijn | 2:89ada0b0b923 | 119 | |
nicovanduijn | 0:4b50c71291e9 | 120 | } |
nicovanduijn | 0:4b50c71291e9 | 121 | |
nicovanduijn | 0:4b50c71291e9 | 122 | ////////////////////////////////////////////////////////////////// |
nicovanduijn | 0:4b50c71291e9 | 123 | // Drive function |
nicovanduijn | 0:4b50c71291e9 | 124 | void drive(float speed) |
nicovanduijn | 0:4b50c71291e9 | 125 | { |
nicovanduijn | 0:4b50c71291e9 | 126 | int direction=0; // Variable to hold direction we want to drive |
nicovanduijn | 0:4b50c71291e9 | 127 | if (speed>0)direction=1; // Positive speed indicates forward |
nicovanduijn | 0:4b50c71291e9 | 128 | if (speed<0)direction=2; // Negative speed indicates backwards |
nicovanduijn | 0:4b50c71291e9 | 129 | if(speed==0)direction=0; // Zero speed indicates stopping |
nicovanduijn | 0:4b50c71291e9 | 130 | switch( direction) { // Depending on what direction was passed |
nicovanduijn | 0:4b50c71291e9 | 131 | case 0: // Stop case |
nicovanduijn | 0:4b50c71291e9 | 132 | motorSpeedLeft=0; // Set the DigitalOuts to stop the motors |
nicovanduijn | 0:4b50c71291e9 | 133 | motorSpeedRight=0; |
nicovanduijn | 0:4b50c71291e9 | 134 | motorDirLeft=0; |
nicovanduijn | 0:4b50c71291e9 | 135 | NmotorDirLeft=0; |
nicovanduijn | 0:4b50c71291e9 | 136 | motorDirRight=0; |
nicovanduijn | 0:4b50c71291e9 | 137 | NmotorDirRight=0; |
nicovanduijn | 0:4b50c71291e9 | 138 | break; |
nicovanduijn | 0:4b50c71291e9 | 139 | case 1: // Forward case |
nicovanduijn | 1:a079ae75a86c | 140 | motorSpeedLeft=speed-turnspeed; // Set the DigitalOuts to run the motors forward |
nicovanduijn | 0:4b50c71291e9 | 141 | motorSpeedRight=speed+turnspeed; |
nicovanduijn | 0:4b50c71291e9 | 142 | motorDirLeft=1; |
nicovanduijn | 0:4b50c71291e9 | 143 | NmotorDirLeft=0; |
nicovanduijn | 0:4b50c71291e9 | 144 | motorDirRight=1; |
nicovanduijn | 0:4b50c71291e9 | 145 | NmotorDirRight=0; |
nicovanduijn | 0:4b50c71291e9 | 146 | break; |
nicovanduijn | 0:4b50c71291e9 | 147 | case 2: // Backwards |
nicovanduijn | 1:a079ae75a86c | 148 | motorSpeedLeft=-speed+turnspeed; // Set the DigitalOuts to run the motors backward |
nicovanduijn | 0:4b50c71291e9 | 149 | motorSpeedRight=-speed-turnspeed; |
nicovanduijn | 0:4b50c71291e9 | 150 | motorDirLeft=0; |
nicovanduijn | 0:4b50c71291e9 | 151 | NmotorDirLeft=1; |
nicovanduijn | 0:4b50c71291e9 | 152 | motorDirRight=0; |
nicovanduijn | 0:4b50c71291e9 | 153 | NmotorDirRight=1; |
nicovanduijn | 0:4b50c71291e9 | 154 | break; |
nicovanduijn | 0:4b50c71291e9 | 155 | default: // Catch-all (Stop) |
nicovanduijn | 0:4b50c71291e9 | 156 | motorSpeedLeft=0; // Set the DigitalOuts to stop the motors |
nicovanduijn | 0:4b50c71291e9 | 157 | motorSpeedRight=0; |
nicovanduijn | 0:4b50c71291e9 | 158 | motorDirLeft=0; |
nicovanduijn | 0:4b50c71291e9 | 159 | NmotorDirLeft=0; |
nicovanduijn | 0:4b50c71291e9 | 160 | motorDirRight=0; |
nicovanduijn | 0:4b50c71291e9 | 161 | NmotorDirRight=0; |
nicovanduijn | 0:4b50c71291e9 | 162 | break; |
nicovanduijn | 0:4b50c71291e9 | 163 | } |
nicovanduijn | 0:4b50c71291e9 | 164 | } |
nicovanduijn | 0:4b50c71291e9 | 165 | |
nicovanduijn | 0:4b50c71291e9 | 166 | ////////////////////////////////////////////////////////////////// |
nicovanduijn | 0:4b50c71291e9 | 167 | // Calibrate function to find gyro drift and accelerometer bias accbias: -0.3 gyrobias: +0.15 |
nicovanduijn | 0:4b50c71291e9 | 168 | void calibrate() |
nicovanduijn | 0:4b50c71291e9 | 169 | { |
nicovanduijn | 1:a079ae75a86c | 170 | for(int i=0; i<100; i++) { // Read a thousand values |
nicovanduijn | 0:4b50c71291e9 | 171 | imu.readAccel(); // Read the Accelerometer |
nicovanduijn | 0:4b50c71291e9 | 172 | imu.readGyro(); // Read the gyro |
nicovanduijn | 0:4b50c71291e9 | 173 | accBias=accBias+(-1)*atan2(imu.ay,imu.az)*180/3.142-90; // Like this, 0 is upright, forward is negative, backward positive |
nicovanduijn | 0:4b50c71291e9 | 174 | gyroBias=gyroBias+imu.gx; // Add up all the gyro Biases |
nicovanduijn | 0:4b50c71291e9 | 175 | } |
nicovanduijn | 1:a079ae75a86c | 176 | accBias=accBias/100; // Convert sum to average |
nicovanduijn | 1:a079ae75a86c | 177 | gyroBias=gyroBias/100; // Convert sum to average |
nicovanduijn | 0:4b50c71291e9 | 178 | } |
nicovanduijn | 0:4b50c71291e9 | 179 | |
nicovanduijn | 3:89e4ed1324bb | 180 | |
nicovanduijn | 3:89e4ed1324bb | 181 | /////////////////////////////////////////////////////////////////// |
nicovanduijn | 3:89e4ed1324bb | 182 | // updateGUI(), triggered by ticker GUI ever 0.5s, sends data to xbee |
nicovanduijn | 3:89e4ed1324bb | 183 | void updateGUI() |
nicovanduijn | 0:4b50c71291e9 | 184 | { |
nicovanduijn | 3:89e4ed1324bb | 185 | xbee.putc('*'); // Send data validity value |
nicovanduijn | 3:89e4ed1324bb | 186 | bytes.f = accBias; // Send accBias |
nicovanduijn | 3:89e4ed1324bb | 187 | xbee.printf("%c%c%c%c", bytes.chars[0], bytes.chars[1], bytes.chars[2], bytes.chars[3]); |
nicovanduijn | 3:89e4ed1324bb | 188 | bytes.f = gyroBias; // Send gyroBias |
nicovanduijn | 3:89e4ed1324bb | 189 | xbee.printf("%c%c%c%c", bytes.chars[0], bytes.chars[1], bytes.chars[2], bytes.chars[3]); |
nicovanduijn | 3:89e4ed1324bb | 190 | bytes.f = pAngle; // Send P Angle |
nicovanduijn | 3:89e4ed1324bb | 191 | xbee.printf("%c%c%c%c", bytes.chars[0], bytes.chars[1], bytes.chars[2], bytes.chars[3]); |
nicovanduijn | 3:89e4ed1324bb | 192 | bytes.f = imu.gx; // Send current angular velocity |
nicovanduijn | 3:89e4ed1324bb | 193 | xbee.printf("%c%c%c%c", bytes.chars[0], bytes.chars[1], bytes.chars[2], bytes.chars[3]); |
nicovanduijn | 3:89e4ed1324bb | 194 | bytes.f = turnspeed; // Send turn speed |
nicovanduijn | 3:89e4ed1324bb | 195 | xbee.printf("%c%c%c%c", bytes.chars[0], bytes.chars[1], bytes.chars[2], bytes.chars[3]); |
nicovanduijn | 3:89e4ed1324bb | 196 | bytes.f = pAngle * kp; // Send P Value |
nicovanduijn | 3:89e4ed1324bb | 197 | xbee.printf("%c%c%c%c", bytes.chars[0], bytes.chars[1], bytes.chars[2], bytes.chars[3]); |
nicovanduijn | 3:89e4ed1324bb | 198 | bytes.f = iAngle * ki; // Send I Value |
nicovanduijn | 3:89e4ed1324bb | 199 | xbee.printf("%c%c%c%c", bytes.chars[0], bytes.chars[1], bytes.chars[2], bytes.chars[3]); |
nicovanduijn | 3:89e4ed1324bb | 200 | bytes.f = dAngle * kd; // Send D Value |
nicovanduijn | 3:89e4ed1324bb | 201 | xbee.printf("%c%c%c%c", bytes.chars[0], bytes.chars[1], bytes.chars[2], bytes.chars[3]); |
nicovanduijn | 3:89e4ed1324bb | 202 | xbee.putc('\n'); // Send delimiting character |
nicovanduijn | 2:89ada0b0b923 | 203 | } |
nicovanduijn | 2:89ada0b0b923 | 204 | ////////////////////////////////////////////////////////////////// |
nicovanduijn | 3:89e4ed1324bb | 205 | // checkValues() updates globals received from xbee |
nicovanduijn | 3:89e4ed1324bb | 206 | void checkValues() |
nicovanduijn | 2:89ada0b0b923 | 207 | { |
nicovanduijn | 3:89e4ed1324bb | 208 | int i=0; // Integer needed for looping through input buffer |
nicovanduijn | 3:89e4ed1324bb | 209 | char buffer[6]; // Buffer to hold all the received data |
nicovanduijn | 3:89e4ed1324bb | 210 | |
nicovanduijn | 3:89e4ed1324bb | 211 | while(xbee.readable()) { // As long as there is stuff in the buffer |
nicovanduijn | 3:89e4ed1324bb | 212 | buffer[i++]=xbee.getc(); // Read from serial |
nicovanduijn | 3:89e4ed1324bb | 213 | } |
nicovanduijn | 3:89e4ed1324bb | 214 | |
nicovanduijn | 3:89e4ed1324bb | 215 | if(buffer[0]== '*') { // Check for 'start' character |
nicovanduijn | 3:89e4ed1324bb | 216 | switch(buffer[1]) { // Switch depending on what value we update |
nicovanduijn | 3:89e4ed1324bb | 217 | case '1': // Updating kp |
nicovanduijn | 3:89e4ed1324bb | 218 | bytes.chars[0] = buffer[2]; |
nicovanduijn | 3:89e4ed1324bb | 219 | bytes.chars[1] = buffer[3]; |
nicovanduijn | 3:89e4ed1324bb | 220 | bytes.chars[2] = buffer[4]; |
nicovanduijn | 3:89e4ed1324bb | 221 | bytes.chars[3] = buffer[5]; |
nicovanduijn | 3:89e4ed1324bb | 222 | kp=bytes.f; |
nicovanduijn | 3:89e4ed1324bb | 223 | break; |
nicovanduijn | 3:89e4ed1324bb | 224 | case '2': // Updating kd |
nicovanduijn | 3:89e4ed1324bb | 225 | bytes.chars[0] = buffer[2]; |
nicovanduijn | 3:89e4ed1324bb | 226 | bytes.chars[1] = buffer[3]; |
nicovanduijn | 3:89e4ed1324bb | 227 | bytes.chars[2] = buffer[4]; |
nicovanduijn | 3:89e4ed1324bb | 228 | bytes.chars[3] = buffer[5]; |
nicovanduijn | 3:89e4ed1324bb | 229 | kd=bytes.f; |
nicovanduijn | 3:89e4ed1324bb | 230 | break; |
nicovanduijn | 3:89e4ed1324bb | 231 | case '3': // Updating ki |
nicovanduijn | 3:89e4ed1324bb | 232 | bytes.chars[0] = buffer[2]; |
nicovanduijn | 3:89e4ed1324bb | 233 | bytes.chars[1] = buffer[3]; |
nicovanduijn | 3:89e4ed1324bb | 234 | bytes.chars[2] = buffer[4]; |
nicovanduijn | 3:89e4ed1324bb | 235 | bytes.chars[3] = buffer[5]; |
nicovanduijn | 3:89e4ed1324bb | 236 | ki=bytes.f; |
nicovanduijn | 3:89e4ed1324bb | 237 | break; |
nicovanduijn | 3:89e4ed1324bb | 238 | case '4': // Updating OVERALL_SCALAR |
nicovanduijn | 3:89e4ed1324bb | 239 | bytes.chars[0] = buffer[2]; |
nicovanduijn | 3:89e4ed1324bb | 240 | bytes.chars[1] = buffer[3]; |
nicovanduijn | 3:89e4ed1324bb | 241 | bytes.chars[2] = buffer[4]; |
nicovanduijn | 3:89e4ed1324bb | 242 | bytes.chars[3] = buffer[5]; |
nicovanduijn | 3:89e4ed1324bb | 243 | OVERALL_SCALAR=bytes.f; |
nicovanduijn | 3:89e4ed1324bb | 244 | break; |
nicovanduijn | 3:89e4ed1324bb | 245 | case '5': // Updating desiredAngle |
nicovanduijn | 3:89e4ed1324bb | 246 | bytes.chars[0] = buffer[2]; |
nicovanduijn | 3:89e4ed1324bb | 247 | bytes.chars[1] = buffer[3]; |
nicovanduijn | 3:89e4ed1324bb | 248 | bytes.chars[2] = buffer[4]; |
nicovanduijn | 3:89e4ed1324bb | 249 | bytes.chars[3] = buffer[5]; |
nicovanduijn | 3:89e4ed1324bb | 250 | desiredAngle=bytes.f; |
nicovanduijn | 3:89e4ed1324bb | 251 | break; |
nicovanduijn | 3:89e4ed1324bb | 252 | case '6': // Updating turnspeed |
nicovanduijn | 3:89e4ed1324bb | 253 | bytes.chars[0] = buffer[2]; |
nicovanduijn | 3:89e4ed1324bb | 254 | bytes.chars[1] = buffer[3]; |
nicovanduijn | 3:89e4ed1324bb | 255 | bytes.chars[2] = buffer[4]; |
nicovanduijn | 3:89e4ed1324bb | 256 | bytes.chars[3] = buffer[5]; |
nicovanduijn | 3:89e4ed1324bb | 257 | turnspeed=bytes.f; |
nicovanduijn | 3:89e4ed1324bb | 258 | } |
nicovanduijn | 3:89e4ed1324bb | 259 | } |
nicovanduijn | 3:89e4ed1324bb | 260 | |
nicovanduijn | 0:4b50c71291e9 | 261 | } |