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@0:8a6003b8bb5b, 2016-02-03 (annotated)
- Committer:
- mborchers
- Date:
- Wed Feb 03 17:19:21 2016 +0000
- Revision:
- 0:8a6003b8bb5b
- Child:
- 1:7eddde9fba60
Erster Commit
Who changed what in which revision?
| User | Revision | Line number | New 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 | 0:8a6003b8bb5b | 5 | #include "Threads/MachineDirectionControl.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 | 0:8a6003b8bb5b | 26 | uint32_t pulse_duration_drive_pwm_current, pulse_duration_drive_pwm_last; |
| mborchers | 0:8a6003b8bb5b | 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 | 0:8a6003b8bb5b | 44 | float velocity_set = 0, steering_angle_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 | 0:8a6003b8bb5b | 49 | |
| mborchers | 0:8a6003b8bb5b | 50 | // Variablen für die Querregelung |
| mborchers | 0:8a6003b8bb5b | 51 | float steering_angle_current = 0, steering_angle_last = 0; |
| mborchers | 0:8a6003b8bb5b | 52 | |
| mborchers | 0:8a6003b8bb5b | 53 | uint8_t timer_steering_angle_sampling_time = 0.01; |
| mborchers | 0:8a6003b8bb5b | 54 | |
| mborchers | 0:8a6003b8bb5b | 55 | float q_Kp = 8.166343211; |
| mborchers | 0:8a6003b8bb5b | 56 | float q_Ki = 18.6661236; |
| mborchers | 0:8a6003b8bb5b | 57 | float feed_forward_control_factor = 13.37091452; |
| mborchers | 0:8a6003b8bb5b | 58 | float q_esum = 0; |
| mborchers | 0:8a6003b8bb5b | 59 | float feed_forward = 0; |
| mborchers | 0:8a6003b8bb5b | 60 | float q_Ki_sampling_time = q_Ki * timer_steering_angle_sampling_time; |
| mborchers | 0:8a6003b8bb5b | 61 | float q_PI_controller, q_PWM, q_e, q_output; |
| mborchers | 0:8a6003b8bb5b | 62 | |
| mborchers | 0:8a6003b8bb5b | 63 | // Variablen für die Querregelung Ende |
| mborchers | 0:8a6003b8bb5b | 64 | |
| mborchers | 0:8a6003b8bb5b | 65 | void serial_thread(void const *args) { |
| mborchers | 0:8a6003b8bb5b | 66 | while (true) { |
| mborchers | 0:8a6003b8bb5b | 67 | Thread::wait(100); |
| mborchers | 0:8a6003b8bb5b | 68 | } |
| mborchers | 0:8a6003b8bb5b | 69 | } |
| mborchers | 0:8a6003b8bb5b | 70 | |
| mborchers | 0:8a6003b8bb5b | 71 | void machine_direction_control(void const *args) { |
| mborchers | 0:8a6003b8bb5b | 72 | osEvent velocity_set_event = machine_direction_queue.get(0); |
| mborchers | 0:8a6003b8bb5b | 73 | if (velocity_set_event.status == osEventMessage) { |
| mborchers | 0:8a6003b8bb5b | 74 | velocity_set = *(float*)velocity_set_event.value.p; |
| mborchers | 0:8a6003b8bb5b | 75 | } |
| mborchers | 0:8a6003b8bb5b | 76 | |
| mborchers | 0:8a6003b8bb5b | 77 | osEvent velocity_current_event = imu_queue_velocity.get(0); |
| mborchers | 0:8a6003b8bb5b | 78 | if (velocity_current_event.status == osEventMessage) { |
| mborchers | 0:8a6003b8bb5b | 79 | velocity_current = *(float *)velocity_current_event.value.p; |
| mborchers | 0:8a6003b8bb5b | 80 | } |
| mborchers | 0:8a6003b8bb5b | 81 | |
| mborchers | 0:8a6003b8bb5b | 82 | drivePWM.pulsewidth_us(1800); |
| mborchers | 0:8a6003b8bb5b | 83 | } |
| mborchers | 0:8a6003b8bb5b | 84 | |
| mborchers | 0:8a6003b8bb5b | 85 | void quadrature_control(void const *args) { |
| mborchers | 0:8a6003b8bb5b | 86 | osEvent steering_angle_set_event = quadrature_queue.get(0); |
| mborchers | 0:8a6003b8bb5b | 87 | if (steering_angle_set_event.status == osEventMessage) { |
| mborchers | 0:8a6003b8bb5b | 88 | steering_angle_set = *(float *)steering_angle_set_event.value.p; |
| mborchers | 0:8a6003b8bb5b | 89 | } |
| mborchers | 0:8a6003b8bb5b | 90 | |
| mborchers | 0:8a6003b8bb5b | 91 | osEvent steering_angle_current_event = imu_queue_steering_angle.get(0); |
| mborchers | 0:8a6003b8bb5b | 92 | if (steering_angle_current_event.status == osEventMessage) { |
| mborchers | 0:8a6003b8bb5b | 93 | steering_angle_current = *(float *)steering_angle_current_event.value.p; |
| mborchers | 0:8a6003b8bb5b | 94 | } |
| mborchers | 0:8a6003b8bb5b | 95 | |
| mborchers | 0:8a6003b8bb5b | 96 | q_e = steering_angle_set - steering_angle_current; |
| mborchers | 0:8a6003b8bb5b | 97 | q_esum = q_esum + q_e; |
| mborchers | 0:8a6003b8bb5b | 98 | |
| mborchers | 0:8a6003b8bb5b | 99 | feed_forward = steering_angle_set * feed_forward_control_factor; |
| mborchers | 0:8a6003b8bb5b | 100 | q_PI_controller = q_Kp*q_e + q_Ki_sampling_time * q_esum; |
| mborchers | 0:8a6003b8bb5b | 101 | |
| mborchers | 0:8a6003b8bb5b | 102 | q_output = feed_forward + q_PI_controller; |
| mborchers | 0:8a6003b8bb5b | 103 | |
| mborchers | 0:8a6003b8bb5b | 104 | if(q_output > 500){q_output = 500;} // evtl Begrenzung schon auf z.b. 300/ -300 stellen (wegen Linearität) |
| mborchers | 0:8a6003b8bb5b | 105 | if(q_output < -500){q_output = - 500;} |
| mborchers | 0:8a6003b8bb5b | 106 | |
| mborchers | 0:8a6003b8bb5b | 107 | q_PWM = 1500 + q_output; |
| mborchers | 0:8a6003b8bb5b | 108 | |
| mborchers | 0:8a6003b8bb5b | 109 | steerPWM.pulsewidth_us(q_PWM); |
| mborchers | 0:8a6003b8bb5b | 110 | } |
| mborchers | 0:8a6003b8bb5b | 111 | |
| mborchers | 0:8a6003b8bb5b | 112 | int main() { |
| mborchers | 0:8a6003b8bb5b | 113 | serialMinnow.baud(115200); |
| mborchers | 0:8a6003b8bb5b | 114 | |
| mborchers | 0:8a6003b8bb5b | 115 | drivePWM.period_ms(20); |
| mborchers | 0:8a6003b8bb5b | 116 | steerPWM.period_ms(20); |
| mborchers | 0:8a6003b8bb5b | 117 | |
| mborchers | 0:8a6003b8bb5b | 118 | SystemTimer *millis = new SystemTimer(); |
| mborchers | 0:8a6003b8bb5b | 119 | |
| mborchers | 0:8a6003b8bb5b | 120 | SupportSystem *supportSystem = new SupportSystem(0x80, &i2c); |
| mborchers | 0:8a6003b8bb5b | 121 | |
| mborchers | 0:8a6003b8bb5b | 122 | Thread machineDirectionControl(test_thread); |
| mborchers | 0:8a6003b8bb5b | 123 | |
| mborchers | 0:8a6003b8bb5b | 124 | RtosTimer machine_direction_control_timer(machine_direction_control); |
| mborchers | 0:8a6003b8bb5b | 125 | RtosTimer quadrature_control_timer(quadrature_control); |
| 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 | 0:8a6003b8bb5b | 144 | velocity_minnow_queue = 12.0; |
| mborchers | 0:8a6003b8bb5b | 145 | quadrature_queue.put(&velocity_minnow_queue); |
| mborchers | 0:8a6003b8bb5b | 146 | |
| mborchers | 0:8a6003b8bb5b | 147 | while(true) { |
| mborchers | 0:8a6003b8bb5b | 148 | IMU_registerDataBuffer = supportSystem->getImuRegisterDataBuffer(); |
| mborchers | 0:8a6003b8bb5b | 149 | RadioDecoder_registerDataBuffer = supportSystem->getRadioDecoderRegisterDataBuffer(); |
| mborchers | 0:8a6003b8bb5b | 150 | |
| mborchers | 0:8a6003b8bb5b | 151 | for(uint8_t i=0; i<3; i++) { |
| mborchers | 0:8a6003b8bb5b | 152 | serialMinnow.printf("RadioDecoder - Ch[%d] Valid: %d\r\n",i,RadioDecoder_registerDataBuffer->channelValid[i]); |
| mborchers | 0:8a6003b8bb5b | 153 | serialMinnow.printf("RadioDecoder - Ch[%d] ActiveTime: %d\r\n",i,RadioDecoder_registerDataBuffer->channelActiveTime[i]); |
| mborchers | 0:8a6003b8bb5b | 154 | serialMinnow.printf("RadioDecoder - Ch[%d] Percentage: %d\r\n",i,RadioDecoder_registerDataBuffer->channelPercent[i]); |
| mborchers | 0:8a6003b8bb5b | 155 | } |
| mborchers | 0:8a6003b8bb5b | 156 | |
| mborchers | 0:8a6003b8bb5b | 157 | uint16_t rc_percentage = RadioDecoder_registerDataBuffer->channelActiveTime[0]; |
| mborchers | 0:8a6003b8bb5b | 158 | uint8_t rc_valid = RadioDecoder_registerDataBuffer->channelValid[0]; |
| mborchers | 0:8a6003b8bb5b | 159 | |
| mborchers | 0:8a6003b8bb5b | 160 | uint16_t drive_percentage = RadioDecoder_registerDataBuffer->channelActiveTime[1]; |
| mborchers | 0:8a6003b8bb5b | 161 | uint8_t drive_valid = RadioDecoder_registerDataBuffer->channelValid[1]; |
| mborchers | 0:8a6003b8bb5b | 162 | |
| mborchers | 0:8a6003b8bb5b | 163 | uint16_t steer_percentage = RadioDecoder_registerDataBuffer->channelActiveTime[2]; |
| mborchers | 0:8a6003b8bb5b | 164 | uint8_t steer_valid = RadioDecoder_registerDataBuffer->channelValid[2]; |
| mborchers | 0:8a6003b8bb5b | 165 | |
| mborchers | 0:8a6003b8bb5b | 166 | |
| mborchers | 0:8a6003b8bb5b | 167 | if (rc_percentage > (uint16_t) 1800 && rc_valid != 0) { |
| mborchers | 0:8a6003b8bb5b | 168 | // oben => Wettbewerb |
| mborchers | 0:8a6003b8bb5b | 169 | heartbeatLED = true; |
| mborchers | 0:8a6003b8bb5b | 170 | buttonLED = false; |
| mborchers | 0:8a6003b8bb5b | 171 | redlightLED = false; |
| mborchers | 0:8a6003b8bb5b | 172 | supportSystem->setLightManagerRemoteLight(false, true); |
| mborchers | 0:8a6003b8bb5b | 173 | if (!timer_started) { |
| mborchers | 0:8a6003b8bb5b | 174 | timer_started = true; |
| mborchers | 0:8a6003b8bb5b | 175 | machine_direction_control_timer.start(10); |
| mborchers | 0:8a6003b8bb5b | 176 | quadrature_control_timer.start(10); |
| mborchers | 0:8a6003b8bb5b | 177 | } |
| mborchers | 0:8a6003b8bb5b | 178 | } else if (rc_percentage > (uint16_t) 1200 && rc_valid != 0) { |
| mborchers | 0:8a6003b8bb5b | 179 | // unten => RC-Wettbewerb |
| mborchers | 0:8a6003b8bb5b | 180 | heartbeatLED = false; |
| mborchers | 0:8a6003b8bb5b | 181 | buttonLED = false; |
| mborchers | 0:8a6003b8bb5b | 182 | redlightLED = true; |
| mborchers | 0:8a6003b8bb5b | 183 | supportSystem->setLightManagerRemoteLight(true, true); |
| mborchers | 0:8a6003b8bb5b | 184 | if (drive_valid) { |
| mborchers | 0:8a6003b8bb5b | 185 | drivePWM.pulsewidth_us(drive_percentage); |
| mborchers | 0:8a6003b8bb5b | 186 | } |
| mborchers | 0:8a6003b8bb5b | 187 | if (steer_valid) { |
| mborchers | 0:8a6003b8bb5b | 188 | steerPWM.pulsewidth_us(steer_percentage); |
| mborchers | 0:8a6003b8bb5b | 189 | } |
| mborchers | 0:8a6003b8bb5b | 190 | if (timer_started) { |
| mborchers | 0:8a6003b8bb5b | 191 | timer_started = false; |
| mborchers | 0:8a6003b8bb5b | 192 | machine_direction_control_timer.stop(); |
| mborchers | 0:8a6003b8bb5b | 193 | quadrature_control_timer.stop(); |
| mborchers | 0:8a6003b8bb5b | 194 | } |
| mborchers | 0:8a6003b8bb5b | 195 | } else if (rc_percentage > (uint16_t) 800 && rc_valid != 0) { |
| mborchers | 0:8a6003b8bb5b | 196 | // mitte => RC-Training |
| mborchers | 0:8a6003b8bb5b | 197 | heartbeatLED = false; |
| mborchers | 0:8a6003b8bb5b | 198 | buttonLED = true; |
| mborchers | 0:8a6003b8bb5b | 199 | redlightLED = false; |
| mborchers | 0:8a6003b8bb5b | 200 | supportSystem->setLightManagerRemoteLight(true, true); |
| mborchers | 0:8a6003b8bb5b | 201 | if (drive_valid) { |
| mborchers | 0:8a6003b8bb5b | 202 | drivePWM.pulsewidth_us(drive_percentage); |
| mborchers | 0:8a6003b8bb5b | 203 | } |
| mborchers | 0:8a6003b8bb5b | 204 | if (steer_valid) { |
| mborchers | 0:8a6003b8bb5b | 205 | steerPWM.pulsewidth_us(steer_percentage); |
| mborchers | 0:8a6003b8bb5b | 206 | } |
| mborchers | 0:8a6003b8bb5b | 207 | if (timer_started) { |
| mborchers | 0:8a6003b8bb5b | 208 | timer_started = false; |
| mborchers | 0:8a6003b8bb5b | 209 | machine_direction_control_timer.stop(); |
| mborchers | 0:8a6003b8bb5b | 210 | quadrature_control_timer.stop(); |
| mborchers | 0:8a6003b8bb5b | 211 | } |
| mborchers | 0:8a6003b8bb5b | 212 | } |
| mborchers | 0:8a6003b8bb5b | 213 | |
| mborchers | 0:8a6003b8bb5b | 214 | velocity_imu_queue = IMU_registerDataBuffer->velocityXFilteredRegister; |
| mborchers | 0:8a6003b8bb5b | 215 | imu_queue_velocity.put(&velocity_imu_queue); |
| mborchers | 0:8a6003b8bb5b | 216 | |
| mborchers | 0:8a6003b8bb5b | 217 | float radius = IMU_registerDataBuffer->velocityXFilteredRegister/IMU_registerDataBuffer->velocityAngularFilteredRegister; |
| mborchers | 0:8a6003b8bb5b | 218 | |
| mborchers | 0:8a6003b8bb5b | 219 | steering_angle_imu_queue = atan(0.205/radius)*180/PI; |
| mborchers | 0:8a6003b8bb5b | 220 | imu_queue_steering_angle.put(&steering_angle_imu_queue); |
| mborchers | 0:8a6003b8bb5b | 221 | |
| mborchers | 0:8a6003b8bb5b | 222 | |
| mborchers | 0:8a6003b8bb5b | 223 | serialMinnow.printf("%f\r\n\r\n", IMU_registerDataBuffer->sensorPositionAngleRegister); |
| mborchers | 0:8a6003b8bb5b | 224 | Thread::wait(50); |
| mborchers | 0:8a6003b8bb5b | 225 | } |
| mborchers | 0:8a6003b8bb5b | 226 | } |
