Oliver Wenzel / Mbed 2 deprecated mbed_amf_controlsystem_iO

Dependencies:   mbed-rtos mbed

Fork of mbed_amf_controlsystem by Matti Borchers

Committer:
mborchers
Date:
Thu Feb 04 17:46:59 2016 +0000
Revision:
7:c5940ae7773a
Parent:
4:f0be27a5a83a
Child:
8:33b8899a8dad
Serial Thread implementiert

Who changed what in which revision?

UserRevisionLine numberNew contents of line
mborchers 0:8a6003b8bb5b 1 #include <mbed.h>
mborchers 0:8a6003b8bb5b 2 #include "rtos.h"
mborchers 0:8a6003b8bb5b 3 #include "Periphery/SupportSystem.h"
mborchers 0:8a6003b8bb5b 4 #include "Misc/SystemTimer.h"
mborchers 3:391c4639bc7d 5 #include "Controller/QuadratureController.h"
mborchers 0:8a6003b8bb5b 6
mborchers 0:8a6003b8bb5b 7 #define PI 3.14159265
mborchers 0:8a6003b8bb5b 8
mborchers 0:8a6003b8bb5b 9 Serial serialMinnow(p13, p14);
mborchers 0:8a6003b8bb5b 10 PwmOut drivePWM(p22);
mborchers 0:8a6003b8bb5b 11 PwmOut steerPWM(p21);
mborchers 0:8a6003b8bb5b 12 I2C i2c(p9, p10);
mborchers 0:8a6003b8bb5b 13
mborchers 0:8a6003b8bb5b 14 DigitalOut heartbeatLED(LED1);
mborchers 0:8a6003b8bb5b 15 DigitalOut buttonLED(LED2);
mborchers 0:8a6003b8bb5b 16 DigitalOut redlightLED(LED3);
mborchers 0:8a6003b8bb5b 17
mborchers 0:8a6003b8bb5b 18 DigitalIn buttonOne(p25);
mborchers 0:8a6003b8bb5b 19 DigitalIn buttonTwo(p26);
mborchers 0:8a6003b8bb5b 20 DigitalIn buttonThree(p29);
mborchers 0:8a6003b8bb5b 21 DigitalIn buttonFour(p30);
mborchers 0:8a6003b8bb5b 22
mborchers 0:8a6003b8bb5b 23 IMU_RegisterDataBuffer_t *IMU_registerDataBuffer;
mborchers 0:8a6003b8bb5b 24 RadioDecoder_RegisterDataBuffer_t *RadioDecoder_registerDataBuffer;
mborchers 0:8a6003b8bb5b 25
mborchers 4:f0be27a5a83a 26 QuadratureController *quadratureController;
mborchers 4:f0be27a5a83a 27
mborchers 0:8a6003b8bb5b 28 // Queues von der Bahnplanung
mborchers 0:8a6003b8bb5b 29 Queue<float, 2> quadrature_queue;
mborchers 0:8a6003b8bb5b 30 Queue<float, 2> machine_direction_queue;
mborchers 0:8a6003b8bb5b 31 float steering_angle_minnow_queue;
mborchers 0:8a6003b8bb5b 32 float velocity_minnow_queue;
mborchers 0:8a6003b8bb5b 33
mborchers 0:8a6003b8bb5b 34
mborchers 0:8a6003b8bb5b 35 // Queues von dem Maussensor
mborchers 0:8a6003b8bb5b 36 Queue<float, 2> imu_queue_velocity;
mborchers 0:8a6003b8bb5b 37 Queue<float, 2> imu_queue_steering_angle;
mborchers 0:8a6003b8bb5b 38 float steering_angle_imu_queue;
mborchers 0:8a6003b8bb5b 39 float velocity_imu_queue;
mborchers 0:8a6003b8bb5b 40
mborchers 0:8a6003b8bb5b 41
mborchers 0:8a6003b8bb5b 42 // Variablen von der Trajektorienplanung
mborchers 0:8a6003b8bb5b 43
mborchers 3:391c4639bc7d 44 float velocity_set = 0;
mborchers 0:8a6003b8bb5b 45
mborchers 0:8a6003b8bb5b 46 // Variablen für die Längsregelung
mborchers 0:8a6003b8bb5b 47 float velocity_current = 0, velocity_last = 0;
mborchers 0:8a6003b8bb5b 48
mborchers 1:7eddde9fba60 49 uint8_t timer_velocity_sampling_time=0.01;
mborchers 1:7eddde9fba60 50 float Vorsteuerungsfaktor;
mborchers 2:bf739d7d9f8f 51 float l_esum, Vorsteuerung, I_Regler, l_output, l_PWM, l_e;
mborchers 1:7eddde9fba60 52 float l_Ki=30*timer_velocity_sampling_time;
mborchers 1:7eddde9fba60 53 uint16_t a[19]={0,600,400,325,250,237,225,212,200,177,144,140,136,132,128,124,120,115,111};
mborchers 1:7eddde9fba60 54
mborchers 1:7eddde9fba60 55 // Querregelung Ende
mborchers 0:8a6003b8bb5b 56
mborchers 0:8a6003b8bb5b 57 void serial_thread(void const *args) {
mborchers 7:c5940ae7773a 58 char c;
mborchers 7:c5940ae7773a 59 float f;
mborchers 0:8a6003b8bb5b 60 while (true) {
mborchers 7:c5940ae7773a 61 serialMinnow.scanf("[%c]=%f\r", &c, &f);
mborchers 7:c5940ae7773a 62 if (c == 'v') {
mborchers 7:c5940ae7773a 63 serialMinnow.printf("v erhalten: %f", c);
mborchers 7:c5940ae7773a 64 } else if (c == 'g') {
mborchers 7:c5940ae7773a 65 serialMinnow.printf("g erhalten: %f", c);
mborchers 7:c5940ae7773a 66 }
mborchers 7:c5940ae7773a 67 heartbeatLED = !heartbeatLED;
mborchers 7:c5940ae7773a 68 //Thread::wait(100);
mborchers 0:8a6003b8bb5b 69 }
mborchers 0:8a6003b8bb5b 70 }
mborchers 0:8a6003b8bb5b 71
mborchers 0:8a6003b8bb5b 72 void machine_direction_control(void const *args) {
mborchers 0:8a6003b8bb5b 73 osEvent velocity_set_event = machine_direction_queue.get(0);
mborchers 0:8a6003b8bb5b 74 if (velocity_set_event.status == osEventMessage) {
mborchers 0:8a6003b8bb5b 75 velocity_set = *(float*)velocity_set_event.value.p;
mborchers 0:8a6003b8bb5b 76 }
mborchers 0:8a6003b8bb5b 77
mborchers 0:8a6003b8bb5b 78 osEvent velocity_current_event = imu_queue_velocity.get(0);
mborchers 0:8a6003b8bb5b 79 if (velocity_current_event.status == osEventMessage) {
mborchers 0:8a6003b8bb5b 80 velocity_current = *(float *)velocity_current_event.value.p;
mborchers 0:8a6003b8bb5b 81 }
mborchers 0:8a6003b8bb5b 82
mborchers 1:7eddde9fba60 83 Vorsteuerungsfaktor = a[(uint8_t)velocity_set*4];
mborchers 1:7eddde9fba60 84 l_e = velocity_set-velocity_current;
mborchers 1:7eddde9fba60 85 l_esum = l_esum + l_e;
mborchers 1:7eddde9fba60 86
mborchers 1:7eddde9fba60 87 Vorsteuerung=Vorsteuerungsfaktor*velocity_set;
mborchers 3:391c4639bc7d 88 I_Regler = l_Ki * l_esum;
mborchers 1:7eddde9fba60 89
mborchers 2:bf739d7d9f8f 90 l_output=Vorsteuerung;//+I_Regler;
mborchers 1:7eddde9fba60 91
mborchers 2:bf739d7d9f8f 92 l_PWM = 1500+l_output;
mborchers 2:bf739d7d9f8f 93
mborchers 2:bf739d7d9f8f 94 if(l_PWM<1500)
mborchers 2:bf739d7d9f8f 95 {
mborchers 2:bf739d7d9f8f 96 l_PWM=1500;
mborchers 2:bf739d7d9f8f 97 }
mborchers 2:bf739d7d9f8f 98 else if(l_PWM>2000)
mborchers 2:bf739d7d9f8f 99 {
mborchers 2:bf739d7d9f8f 100 l_PWM=2000;
mborchers 2:bf739d7d9f8f 101 }
mborchers 1:7eddde9fba60 102
mborchers 1:7eddde9fba60 103 drivePWM.pulsewidth_us(l_PWM);
mborchers 0:8a6003b8bb5b 104 }
mborchers 0:8a6003b8bb5b 105
mborchers 4:f0be27a5a83a 106 void redirect_quadrature_controller(void const *args) {
mborchers 4:f0be27a5a83a 107 quadratureController->cylic_control();
mborchers 4:f0be27a5a83a 108 }
mborchers 4:f0be27a5a83a 109
mborchers 0:8a6003b8bb5b 110 int main() {
mborchers 0:8a6003b8bb5b 111 serialMinnow.baud(115200);
mborchers 0:8a6003b8bb5b 112
mborchers 0:8a6003b8bb5b 113 drivePWM.period_ms(20);
mborchers 0:8a6003b8bb5b 114 steerPWM.period_ms(20);
mborchers 0:8a6003b8bb5b 115
mborchers 0:8a6003b8bb5b 116 SystemTimer *millis = new SystemTimer();
mborchers 0:8a6003b8bb5b 117
mborchers 0:8a6003b8bb5b 118 SupportSystem *supportSystem = new SupportSystem(0x80, &i2c);
mborchers 3:391c4639bc7d 119
mborchers 4:f0be27a5a83a 120 quadratureController = new QuadratureController(&steerPWM);
mborchers 0:8a6003b8bb5b 121
mborchers 1:7eddde9fba60 122 Thread machineDirectionControl(serial_thread);
mborchers 0:8a6003b8bb5b 123
mborchers 0:8a6003b8bb5b 124 RtosTimer machine_direction_control_timer(machine_direction_control);
mborchers 4:f0be27a5a83a 125 RtosTimer quadrature_control_timer(redirect_quadrature_controller);
mborchers 0:8a6003b8bb5b 126
mborchers 0:8a6003b8bb5b 127 // Konfiguration AMF-IMU
mborchers 0:8a6003b8bb5b 128 // [0]: Conversation Factor
mborchers 0:8a6003b8bb5b 129 // [1]: Sensor Position X
mborchers 0:8a6003b8bb5b 130 // [2]: Sensor Position Y
mborchers 0:8a6003b8bb5b 131 // [3]: Sensor Position Angle
mborchers 0:8a6003b8bb5b 132 float configData[4] = {0.002751114f, 167.0f, 0.0f, 269.0f};
mborchers 0:8a6003b8bb5b 133
mborchers 0:8a6003b8bb5b 134 supportSystem->writeData(SUPPORT_SYSTEM_REGISTER_ADDRESS_IMU_CONVERSION_FACTOR, configData, sizeof(float)*4);
mborchers 0:8a6003b8bb5b 135
mborchers 0:8a6003b8bb5b 136 // Flag setzen
mborchers 0:8a6003b8bb5b 137 uint8_t command = 1<<3;
mborchers 0:8a6003b8bb5b 138 supportSystem->writeData(SUPPORT_SYSTEM_REGISTER_ADDRESS_IMU_COMMAND, &command, sizeof(uint8_t));
mborchers 0:8a6003b8bb5b 139
mborchers 0:8a6003b8bb5b 140 bool timer_started = false;
mborchers 0:8a6003b8bb5b 141
mborchers 0:8a6003b8bb5b 142 wait(0.1);
mborchers 0:8a6003b8bb5b 143
mborchers 2:bf739d7d9f8f 144 steering_angle_minnow_queue = 0.0;
mborchers 2:bf739d7d9f8f 145 quadrature_queue.put(&steering_angle_minnow_queue);
mborchers 2:bf739d7d9f8f 146
mborchers 2:bf739d7d9f8f 147 velocity_minnow_queue = 1.5;
mborchers 2:bf739d7d9f8f 148 machine_direction_queue.put(&velocity_minnow_queue);
mborchers 0:8a6003b8bb5b 149
mborchers 0:8a6003b8bb5b 150 while(true) {
mborchers 0:8a6003b8bb5b 151 IMU_registerDataBuffer = supportSystem->getImuRegisterDataBuffer();
mborchers 0:8a6003b8bb5b 152 RadioDecoder_registerDataBuffer = supportSystem->getRadioDecoderRegisterDataBuffer();
mborchers 0:8a6003b8bb5b 153
mborchers 7:c5940ae7773a 154 //for(uint8_t i=0; i<3; i++) {
mborchers 7:c5940ae7773a 155 // serialMinnow.printf("RadioDecoder - Ch[%d] Valid: %d\r\n",i,RadioDecoder_registerDataBuffer->channelValid[i]);
mborchers 7:c5940ae7773a 156 // serialMinnow.printf("RadioDecoder - Ch[%d] ActiveTime: %d\r\n",i,RadioDecoder_registerDataBuffer->channelActiveTime[i]);
mborchers 7:c5940ae7773a 157 // serialMinnow.printf("RadioDecoder - Ch[%d] Percentage: %d\r\n\r\n",i,RadioDecoder_registerDataBuffer->channelPercent[i]);
mborchers 7:c5940ae7773a 158 //}
mborchers 0:8a6003b8bb5b 159
mborchers 0:8a6003b8bb5b 160 uint16_t rc_percentage = RadioDecoder_registerDataBuffer->channelActiveTime[0];
mborchers 0:8a6003b8bb5b 161 uint8_t rc_valid = RadioDecoder_registerDataBuffer->channelValid[0];
mborchers 0:8a6003b8bb5b 162
mborchers 0:8a6003b8bb5b 163 uint16_t drive_percentage = RadioDecoder_registerDataBuffer->channelActiveTime[1];
mborchers 0:8a6003b8bb5b 164 uint8_t drive_valid = RadioDecoder_registerDataBuffer->channelValid[1];
mborchers 0:8a6003b8bb5b 165
mborchers 0:8a6003b8bb5b 166 uint16_t steer_percentage = RadioDecoder_registerDataBuffer->channelActiveTime[2];
mborchers 0:8a6003b8bb5b 167 uint8_t steer_valid = RadioDecoder_registerDataBuffer->channelValid[2];
mborchers 0:8a6003b8bb5b 168
mborchers 0:8a6003b8bb5b 169
mborchers 0:8a6003b8bb5b 170 if (rc_percentage > (uint16_t) 1800 && rc_valid != 0) {
mborchers 0:8a6003b8bb5b 171 // oben => Wettbewerb
mborchers 7:c5940ae7773a 172 //heartbeatLED = true;
mborchers 0:8a6003b8bb5b 173 buttonLED = false;
mborchers 0:8a6003b8bb5b 174 redlightLED = false;
mborchers 0:8a6003b8bb5b 175 supportSystem->setLightManagerRemoteLight(false, true);
mborchers 0:8a6003b8bb5b 176 if (!timer_started) {
mborchers 0:8a6003b8bb5b 177 timer_started = true;
mborchers 0:8a6003b8bb5b 178 machine_direction_control_timer.start(10);
mborchers 0:8a6003b8bb5b 179 quadrature_control_timer.start(10);
mborchers 0:8a6003b8bb5b 180 }
mborchers 0:8a6003b8bb5b 181 } else if (rc_percentage > (uint16_t) 1200 && rc_valid != 0) {
mborchers 0:8a6003b8bb5b 182 // unten => RC-Wettbewerb
mborchers 7:c5940ae7773a 183 //heartbeatLED = false;
mborchers 0:8a6003b8bb5b 184 buttonLED = false;
mborchers 0:8a6003b8bb5b 185 redlightLED = true;
mborchers 0:8a6003b8bb5b 186 supportSystem->setLightManagerRemoteLight(true, true);
mborchers 0:8a6003b8bb5b 187 if (drive_valid) {
mborchers 0:8a6003b8bb5b 188 drivePWM.pulsewidth_us(drive_percentage);
mborchers 0:8a6003b8bb5b 189 }
mborchers 0:8a6003b8bb5b 190 if (steer_valid) {
mborchers 0:8a6003b8bb5b 191 steerPWM.pulsewidth_us(steer_percentage);
mborchers 0:8a6003b8bb5b 192 }
mborchers 0:8a6003b8bb5b 193 if (timer_started) {
mborchers 0:8a6003b8bb5b 194 timer_started = false;
mborchers 0:8a6003b8bb5b 195 machine_direction_control_timer.stop();
mborchers 0:8a6003b8bb5b 196 quadrature_control_timer.stop();
mborchers 0:8a6003b8bb5b 197 }
mborchers 0:8a6003b8bb5b 198 } else if (rc_percentage > (uint16_t) 800 && rc_valid != 0) {
mborchers 0:8a6003b8bb5b 199 // mitte => RC-Training
mborchers 7:c5940ae7773a 200 //heartbeatLED = false;
mborchers 0:8a6003b8bb5b 201 buttonLED = true;
mborchers 0:8a6003b8bb5b 202 redlightLED = false;
mborchers 0:8a6003b8bb5b 203 supportSystem->setLightManagerRemoteLight(true, true);
mborchers 0:8a6003b8bb5b 204 if (drive_valid) {
mborchers 0:8a6003b8bb5b 205 drivePWM.pulsewidth_us(drive_percentage);
mborchers 0:8a6003b8bb5b 206 }
mborchers 0:8a6003b8bb5b 207 if (steer_valid) {
mborchers 0:8a6003b8bb5b 208 steerPWM.pulsewidth_us(steer_percentage);
mborchers 0:8a6003b8bb5b 209 }
mborchers 0:8a6003b8bb5b 210 if (timer_started) {
mborchers 0:8a6003b8bb5b 211 timer_started = false;
mborchers 0:8a6003b8bb5b 212 machine_direction_control_timer.stop();
mborchers 0:8a6003b8bb5b 213 quadrature_control_timer.stop();
mborchers 0:8a6003b8bb5b 214 }
mborchers 0:8a6003b8bb5b 215 }
mborchers 0:8a6003b8bb5b 216
mborchers 0:8a6003b8bb5b 217 velocity_imu_queue = IMU_registerDataBuffer->velocityXFilteredRegister;
mborchers 0:8a6003b8bb5b 218 imu_queue_velocity.put(&velocity_imu_queue);
mborchers 0:8a6003b8bb5b 219
mborchers 0:8a6003b8bb5b 220 float radius = IMU_registerDataBuffer->velocityXFilteredRegister/IMU_registerDataBuffer->velocityAngularFilteredRegister;
mborchers 0:8a6003b8bb5b 221
mborchers 0:8a6003b8bb5b 222 steering_angle_imu_queue = atan(0.205/radius)*180/PI;
mborchers 0:8a6003b8bb5b 223 imu_queue_steering_angle.put(&steering_angle_imu_queue);
mborchers 0:8a6003b8bb5b 224
mborchers 0:8a6003b8bb5b 225
mborchers 2:bf739d7d9f8f 226 //serialMinnow.printf("%ld, ", difference_millis);
mborchers 7:c5940ae7773a 227 //serialMinnow.printf("%f, ", velocity_minnow_queue);
mborchers 7:c5940ae7773a 228 //serialMinnow.printf("%f, ", steering_angle_minnow_queue);
mborchers 7:c5940ae7773a 229 //serialMinnow.printf("%d, ", IMU_registerDataBuffer->curveRadiusRegister);
mborchers 7:c5940ae7773a 230 //serialMinnow.printf("%f, ", IMU_registerDataBuffer->velocityAngularRegister);
mborchers 7:c5940ae7773a 231 //serialMinnow.printf("%f, ", IMU_registerDataBuffer->velocityAngularFilteredRegister);
mborchers 7:c5940ae7773a 232 //serialMinnow.printf("%f, ", IMU_registerDataBuffer->velocityXRegister);
mborchers 7:c5940ae7773a 233 //serialMinnow.printf("%f\r\n", IMU_registerDataBuffer->velocityXFilteredRegister);
mborchers 0:8a6003b8bb5b 234 Thread::wait(50);
mborchers 0:8a6003b8bb5b 235 }
mborchers 0:8a6003b8bb5b 236 }