SmartWheels self-driving race car. Designed for NXP Cup. Uses FRDM-KL25Z, area-scan camera, and simple image processing to detect and navigate any NXP spec track.
Dependencies: TSI USBDevice mbed-dev
Fork of SmartWheels by
main.cpp@56:7d3395ae022d, 2017-04-06 (annotated)
- Committer:
- hazheng
- Date:
- Thu Apr 06 22:19:59 2017 +0000
- Revision:
- 56:7d3395ae022d
- Parent:
- 55:d4db9eef4a9d
- Child:
- 57:0d8a155d511d
Added debug log function.
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
hazheng | 3:c8867972ffc7 | 1 | #include "mbed.h" |
hazheng | 5:577b582e4fe9 | 2 | |
hazheng | 44:15de535c4005 | 3 | #include <math.h> |
hazheng | 46:a5eb9bd3bb55 | 4 | #define PI 3.14159265f |
hazheng | 44:15de535c4005 | 5 | |
hazheng | 56:7d3395ae022d | 6 | #define SW_DEBUG |
hazheng | 56:7d3395ae022d | 7 | #include "SWCommon.h" |
hazheng | 56:7d3395ae022d | 8 | #include "GlobalVariable.h" |
hazheng | 56:7d3395ae022d | 9 | |
Bobymicjohn | 8:92f6baeea027 | 10 | #include "Motor.h" |
Bobymicjohn | 11:676ea42afd56 | 11 | #include "Servo.h" |
Bobymicjohn | 15:eb6a274b3dfb | 12 | #include "WheelEncoder.h" |
Bobymicjohn | 11:676ea42afd56 | 13 | #include "Core.h" |
Bobymicjohn | 11:676ea42afd56 | 14 | #include "SWUSBServer.h" |
hazheng | 29:f87d8790f57d | 15 | |
hazheng | 29:f87d8790f57d | 16 | #include "ArduCAM.h" |
hazheng | 40:be98219930e4 | 17 | #include "ArduUTFT.h" |
Bobymicjohn | 10:fedb5786a109 | 18 | |
Bobymicjohn | 10:fedb5786a109 | 19 | #include "PinAssignment.h" |
Bobymicjohn | 8:92f6baeea027 | 20 | |
hazheng | 28:271fc8445e89 | 21 | SPI g_spi_port(PIN_SPI_MOSI, PIN_SPI_MISO, PIN_SPI_SCK); |
hazheng | 29:f87d8790f57d | 22 | SW::Core g_core; |
hazheng | 5:577b582e4fe9 | 23 | |
hazheng | 56:7d3395ae022d | 24 | #ifdef SW_DEBUG |
hazheng | 56:7d3395ae022d | 25 | #include <rtos.h> |
hazheng | 56:7d3395ae022d | 26 | Mutex g_sw_spi_lock; |
hazheng | 56:7d3395ae022d | 27 | #endif |
hazheng | 56:7d3395ae022d | 28 | |
hazheng | 3:c8867972ffc7 | 29 | int main(void) { |
hazheng | 16:66c7a09e71ee | 30 | |
hazheng | 16:66c7a09e71ee | 31 | Timer timer; |
hazheng | 16:66c7a09e71ee | 32 | |
hazheng | 48:f76b5e252444 | 33 | g_spi_port.frequency(5000000); |
hazheng | 29:f87d8790f57d | 34 | //g_spi_port.format(8, 0); |
hazheng | 29:f87d8790f57d | 35 | |
hazheng | 29:f87d8790f57d | 36 | //SW::Core core; |
Bobymicjohn | 10:fedb5786a109 | 37 | |
hazheng | 46:a5eb9bd3bb55 | 38 | //Motor motor(g_core); |
hazheng | 45:501b7909139a | 39 | //Servo servo(g_core); |
hazheng | 25:6f63053cee81 | 40 | //WheelEncoder wheelEncoder(core); |
hazheng | 29:f87d8790f57d | 41 | //Camera cam(core); |
hazheng | 46:a5eb9bd3bb55 | 42 | motor_init(); |
hazheng | 45:501b7909139a | 43 | servo_init(); |
hazheng | 16:66c7a09e71ee | 44 | |
hazheng | 29:f87d8790f57d | 45 | bool isRegRead = false; |
Bobymicjohn | 14:88302da8bff0 | 46 | |
hazheng | 40:be98219930e4 | 47 | |
hazheng | 40:be98219930e4 | 48 | ardu_utft_init(); |
hazheng | 29:f87d8790f57d | 49 | |
hazheng | 41:7b21c5e3599e | 50 | |
hazheng | 41:7b21c5e3599e | 51 | ardu_cam_init(); |
hazheng | 41:7b21c5e3599e | 52 | |
hazheng | 18:bf6c5f8281eb | 53 | //timer.reset(); |
hazheng | 16:66c7a09e71ee | 54 | timer.start(); |
hazheng | 18:bf6c5f8281eb | 55 | float timeWas = timer.read(); |
hazheng | 44:15de535c4005 | 56 | |
hazheng | 46:a5eb9bd3bb55 | 57 | servo_set_angle(0.0f); |
Bobymicjohn | 54:f1f5648dfacf | 58 | |
Bobymicjohn | 54:f1f5648dfacf | 59 | float speedRatio = 1.0f; |
Bobymicjohn | 54:f1f5648dfacf | 60 | |
hazheng | 5:577b582e4fe9 | 61 | while (1) |
hazheng | 5:577b582e4fe9 | 62 | { |
hazheng | 18:bf6c5f8281eb | 63 | float deltaTime = timeWas; |
hazheng | 18:bf6c5f8281eb | 64 | timeWas = timer.read(); |
hazheng | 18:bf6c5f8281eb | 65 | deltaTime = timeWas - deltaTime; |
hazheng | 18:bf6c5f8281eb | 66 | |
Bobymicjohn | 54:f1f5648dfacf | 67 | //g_core.Update(deltaTime); |
hazheng | 41:7b21c5e3599e | 68 | |
Bobymicjohn | 54:f1f5648dfacf | 69 | //if(!isRegRead && g_core.GetUSBServer().GetStatus() == SER_STAT_RUNNING && timer.read() > 2.5f && ardu_cam_is_capture_finished()) |
Bobymicjohn | 54:f1f5648dfacf | 70 | //{ |
hazheng | 44:15de535c4005 | 71 | //ardu_cam_print_debug(); |
Bobymicjohn | 54:f1f5648dfacf | 72 | // isRegRead = true; |
Bobymicjohn | 54:f1f5648dfacf | 73 | //} |
hazheng | 41:7b21c5e3599e | 74 | |
hazheng | 44:15de535c4005 | 75 | //ardu_cam_display_img_utft(); |
hazheng | 46:a5eb9bd3bb55 | 76 | |
hazheng | 55:d4db9eef4a9d | 77 | const volatile uint8_t * centerLine = ardu_cam_get_center_array(); |
hazheng | 46:a5eb9bd3bb55 | 78 | |
hazheng | 46:a5eb9bd3bb55 | 79 | /////////////Calculate the curvature: |
Bobymicjohn | 54:f1f5648dfacf | 80 | float srcY = (0.0f) / 1.0f; |
Bobymicjohn | 54:f1f5648dfacf | 81 | float srcX = static_cast<float>(centerLine[0]) / 1.0f; |
hazheng | 46:a5eb9bd3bb55 | 82 | |
Bobymicjohn | 54:f1f5648dfacf | 83 | float destY = static_cast<float>(CAM_ROI_UPPER_LIMIT - 1) / 1.0f; |
Bobymicjohn | 54:f1f5648dfacf | 84 | float destX = static_cast<float>(centerLine[CAM_ROI_UPPER_LIMIT - 1]) / 1.0f; |
hazheng | 46:a5eb9bd3bb55 | 85 | |
hazheng | 46:a5eb9bd3bb55 | 86 | float disY = destY - srcY; |
hazheng | 46:a5eb9bd3bb55 | 87 | float disX = destX - srcX; |
hazheng | 46:a5eb9bd3bb55 | 88 | |
hazheng | 52:078b521c9edf | 89 | float angleRadians = -1.0f * static_cast<float>(atan(static_cast<double>(disX / disY))); |
Bobymicjohn | 47:a682be9908b9 | 90 | |
Bobymicjohn | 47:a682be9908b9 | 91 | float angleDegrees = (angleRadians * (180.0f / PI)); |
hazheng | 46:a5eb9bd3bb55 | 92 | /////////////////////////////////////// |
hazheng | 46:a5eb9bd3bb55 | 93 | |
hazheng | 46:a5eb9bd3bb55 | 94 | /////////////Calculate the offset: |
hazheng | 44:15de535c4005 | 95 | float centerPos = static_cast<float>(RESOLUTION_WIDTH / 2); |
hazheng | 52:078b521c9edf | 96 | float offsetDegrees = ((srcX - centerPos) / centerPos) * SERVO_MAX_ANGLE; |
hazheng | 46:a5eb9bd3bb55 | 97 | ////////////////////////////////////// |
hazheng | 46:a5eb9bd3bb55 | 98 | |
Bobymicjohn | 54:f1f5648dfacf | 99 | float totalAngleDegrees = (angleDegrees * 0.70f) + (offsetDegrees * 0.50f); |
Bobymicjohn | 54:f1f5648dfacf | 100 | float totalAngleDegreesAbs = abs(totalAngleDegrees); |
hazheng | 52:078b521c9edf | 101 | servo_set_angle(totalAngleDegrees); |
hazheng | 52:078b521c9edf | 102 | |
hazheng | 52:078b521c9edf | 103 | if(totalAngleDegrees > SERVO_MAX_ANGLE) |
hazheng | 52:078b521c9edf | 104 | totalAngleDegrees = SERVO_MAX_ANGLE; |
hazheng | 52:078b521c9edf | 105 | else if(totalAngleDegrees < -SERVO_MAX_ANGLE) |
hazheng | 52:078b521c9edf | 106 | totalAngleDegrees = -SERVO_MAX_ANGLE; |
Bobymicjohn | 54:f1f5648dfacf | 107 | |
Bobymicjohn | 54:f1f5648dfacf | 108 | |
Bobymicjohn | 54:f1f5648dfacf | 109 | if(totalAngleDegreesAbs > 17.0f) |
hazheng | 52:078b521c9edf | 110 | { |
Bobymicjohn | 54:f1f5648dfacf | 111 | speedRatio = 0.4f; |
Bobymicjohn | 54:f1f5648dfacf | 112 | } |
Bobymicjohn | 54:f1f5648dfacf | 113 | else if(totalAngleDegreesAbs > 12.0f) |
Bobymicjohn | 54:f1f5648dfacf | 114 | { |
Bobymicjohn | 54:f1f5648dfacf | 115 | speedRatio = 0.6f; |
Bobymicjohn | 54:f1f5648dfacf | 116 | } |
Bobymicjohn | 54:f1f5648dfacf | 117 | else if(totalAngleDegreesAbs > 7.0f) |
Bobymicjohn | 54:f1f5648dfacf | 118 | { |
Bobymicjohn | 54:f1f5648dfacf | 119 | speedRatio = 0.8f; |
hazheng | 52:078b521c9edf | 120 | } |
hazheng | 52:078b521c9edf | 121 | else |
hazheng | 52:078b521c9edf | 122 | { |
Bobymicjohn | 54:f1f5648dfacf | 123 | speedRatio = 1.0f; |
Bobymicjohn | 54:f1f5648dfacf | 124 | } |
Bobymicjohn | 54:f1f5648dfacf | 125 | |
Bobymicjohn | 54:f1f5648dfacf | 126 | if(totalAngleDegrees < 0.0f) |
Bobymicjohn | 54:f1f5648dfacf | 127 | { |
Bobymicjohn | 54:f1f5648dfacf | 128 | motor_set_left_speed(speedRatio * ((MOTOR_DIFF_MIN_SPEED) + ((1.0f - MOTOR_DIFF_MIN_SPEED) * ((SERVO_MAX_ANGLE - abs(totalAngleDegrees)) / SERVO_MAX_ANGLE)))); |
Bobymicjohn | 54:f1f5648dfacf | 129 | motor_set_right_speed(speedRatio * 1.0f); |
Bobymicjohn | 54:f1f5648dfacf | 130 | } |
Bobymicjohn | 54:f1f5648dfacf | 131 | else |
Bobymicjohn | 54:f1f5648dfacf | 132 | { |
Bobymicjohn | 54:f1f5648dfacf | 133 | motor_set_right_speed(speedRatio * ((MOTOR_DIFF_MIN_SPEED) + ((1.0f - MOTOR_DIFF_MIN_SPEED) * ((SERVO_MAX_ANGLE - abs(totalAngleDegrees)) / SERVO_MAX_ANGLE)))); |
Bobymicjohn | 54:f1f5648dfacf | 134 | motor_set_left_speed(speedRatio * 1.0f); |
hazheng | 52:078b521c9edf | 135 | } |
hazheng | 56:7d3395ae022d | 136 | |
hazheng | 56:7d3395ae022d | 137 | LOGI("FPS: %f", 1 / deltaTime); |
hazheng | 52:078b521c9edf | 138 | /* |
Bobymicjohn | 47:a682be9908b9 | 139 | //////// Steer Vehicle / Adjust Speed for Differential ////////// |
Bobymicjohn | 47:a682be9908b9 | 140 | servo_set_angle((angleDegrees * -0.3f) + (offsetPercent * SERVO_MAX_ANGLE * 0.3f)); |
Bobymicjohn | 47:a682be9908b9 | 141 | |
Bobymicjohn | 47:a682be9908b9 | 142 | if(angleRadians > 0.366) |
Bobymicjohn | 47:a682be9908b9 | 143 | angleRadians = 0.366; |
Bobymicjohn | 47:a682be9908b9 | 144 | else if(angleRadians < -0.366) |
Bobymicjohn | 47:a682be9908b9 | 145 | angleRadians = -0.366; |
Bobymicjohn | 47:a682be9908b9 | 146 | |
Bobymicjohn | 47:a682be9908b9 | 147 | if(angleRadians < 0) |
Bobymicjohn | 47:a682be9908b9 | 148 | { |
Bobymicjohn | 47:a682be9908b9 | 149 | motor_set_left_speed((0.5) + (0.5) * ((0.366 - abs(angleRadians))/0.366)); |
Bobymicjohn | 47:a682be9908b9 | 150 | motor_set_right_speed(1.0); |
Bobymicjohn | 47:a682be9908b9 | 151 | } |
Bobymicjohn | 47:a682be9908b9 | 152 | else |
Bobymicjohn | 47:a682be9908b9 | 153 | { |
Bobymicjohn | 47:a682be9908b9 | 154 | motor_set_right_speed((0.5) + (0.5) * ((0.366 - abs(angleRadians))/0.366)); |
Bobymicjohn | 47:a682be9908b9 | 155 | motor_set_left_speed(1.0); |
Bobymicjohn | 47:a682be9908b9 | 156 | } |
hazheng | 52:078b521c9edf | 157 | */ |
hazheng | 50:c387c88141fb | 158 | |
hazheng | 50:c387c88141fb | 159 | |
hazheng | 46:a5eb9bd3bb55 | 160 | //char buf[20]; |
hazheng | 46:a5eb9bd3bb55 | 161 | //sprintf(buf, "angle %f", angle); |
hazheng | 46:a5eb9bd3bb55 | 162 | //g_core.GetUSBServer().PushUnreliableMsg('D', buf); |
hazheng | 46:a5eb9bd3bb55 | 163 | /* |
hazheng | 46:a5eb9bd3bb55 | 164 | std::string tempStr = "XX"; |
hazheng | 46:a5eb9bd3bb55 | 165 | for(uint8_t i = 0; i < CAM_ROI_UPPER_LIMIT; ++i) |
hazheng | 46:a5eb9bd3bb55 | 166 | { |
hazheng | 46:a5eb9bd3bb55 | 167 | tempStr[0] = i; |
hazheng | 46:a5eb9bd3bb55 | 168 | tempStr[1] = centerLine[i]; |
hazheng | 46:a5eb9bd3bb55 | 169 | g_core.GetUSBServer().PushUnreliableMsg('L', tempStr); |
hazheng | 46:a5eb9bd3bb55 | 170 | } |
hazheng | 46:a5eb9bd3bb55 | 171 | */ |
hazheng | 46:a5eb9bd3bb55 | 172 | |
hazheng | 46:a5eb9bd3bb55 | 173 | /* |
hazheng | 44:15de535c4005 | 174 | if(offsetPercent > 0.1) |
hazheng | 44:15de535c4005 | 175 | { |
hazheng | 46:a5eb9bd3bb55 | 176 | motor_set_speeds(0.05f, 0.05f); |
hazheng | 44:15de535c4005 | 177 | } |
hazheng | 44:15de535c4005 | 178 | else |
hazheng | 44:15de535c4005 | 179 | { |
hazheng | 46:a5eb9bd3bb55 | 180 | motor_set_speeds(0.13f, 0.13f); |
hazheng | 44:15de535c4005 | 181 | } |
hazheng | 46:a5eb9bd3bb55 | 182 | */ |
hazheng | 43:0d1886f4848a | 183 | //wait(0.01); |
hazheng | 3:c8867972ffc7 | 184 | } |
hazheng | 3:c8867972ffc7 | 185 | } |
hazheng | 3:c8867972ffc7 | 186 | |
hazheng | 3:c8867972ffc7 | 187 | /* |
hazheng | 3:c8867972ffc7 | 188 | PwmOut servo(PTE20); |
hazheng | 3:c8867972ffc7 | 189 | |
hazheng | 3:c8867972ffc7 | 190 | int main() { |
hazheng | 3:c8867972ffc7 | 191 | servo.period(0.020); // servo requires a 20ms period |
hazheng | 3:c8867972ffc7 | 192 | |
hazheng | 3:c8867972ffc7 | 193 | while (1) { |
hazheng | 3:c8867972ffc7 | 194 | for(float offset=0.0; offset<0.001; offset+=0.0001) { |
hazheng | 3:c8867972ffc7 | 195 | servo.pulsewidth(0.001 + offset); // servo position determined by a pulsewidth between 1-2ms |
hazheng | 3:c8867972ffc7 | 196 | wait(0.25); |
hazheng | 3:c8867972ffc7 | 197 | } |
hazheng | 3:c8867972ffc7 | 198 | } |
hazheng | 3:c8867972ffc7 | 199 | |
hazheng | 3:c8867972ffc7 | 200 | } |
hazheng | 13:7dcb1642ef99 | 201 | */ |
hazheng | 13:7dcb1642ef99 | 202 | |
hazheng | 13:7dcb1642ef99 | 203 | /* //code for accelerometer sensor. |
hazheng | 13:7dcb1642ef99 | 204 | const char regAddr = 0x0D; |
hazheng | 13:7dcb1642ef99 | 205 | char readValue = 0; |
hazheng | 13:7dcb1642ef99 | 206 | int result1 = m_sccbCtrl.write(0x1D<<1, ®Addr, 1, true); |
hazheng | 13:7dcb1642ef99 | 207 | int result2 = m_sccbCtrl.read(0x1D<<1, &readValue, 1, false); |
hazheng | 13:7dcb1642ef99 | 208 | char buf[20]; |
hazheng | 13:7dcb1642ef99 | 209 | sprintf(buf, "%#x-%#x-%d-%d", regAddr, readValue, result1, result2); |
hazheng | 13:7dcb1642ef99 | 210 | m_core.GetUSBServer().PushUnreliableMsg('D', buf); |
hazheng | 3:c8867972ffc7 | 211 | */ |