GPS and IMU reading works

Dependencies:   mbed Servo SDFileSystem

/media/uploads/taoqiuyang/img_2352.jpg

Committer:
taoqiuyang
Date:
Thu Sep 10 18:15:16 2015 +0000
Revision:
26:353a80179346
Parent:
24:8e38cc14150c
Child:
27:1be1f25be449
Added first version of navigation controller

Who changed what in which revision?

UserRevisionLine numberNew contents of line
dem123456789 20:a820531c78bc 1 #include "Config.h"
dem123456789 11:1caacb994236 2
taoqiuyang 2:afb333543af5 3 DigitalOut led1(LED1);
taoqiuyang 2:afb333543af5 4 DigitalOut led2(LED2);
taoqiuyang 5:451b8203ef99 5 DigitalOut led3(LED3);
dem123456789 8:1f5a44bade4d 6 DigitalOut led4(LED4);
dem123456789 20:a820531c78bc 7
taoqiuyang 2:afb333543af5 8 Serial pc(USBTX, USBRX);
taoqiuyang 2:afb333543af5 9 Serial IMU(p28, p27); // tx, rx
taoqiuyang 5:451b8203ef99 10 Serial GPS(p13, p14); // tx, rx
dem123456789 21:99be83550601 11 Servo rudderServo(p25);
dem123456789 21:99be83550601 12 Servo wingServo(p26);
dem123456789 21:99be83550601 13 SDFileSystem sd(p5, p6, p7, p8, "sd");// mosi, miso, sck, cs
taoqiuyang 26:353a80179346 14 Ticker ctrl_updt_timer; //timer to refresh controller
taoqiuyang 2:afb333543af5 15
taoqiuyang 2:afb333543af5 16 char IMU_message[256];
taoqiuyang 3:ab9f94d112c0 17 int IMU_message_counter=0;
taoqiuyang 5:451b8203ef99 18 char GPS_message[256];
taoqiuyang 5:451b8203ef99 19 int GPS_message_counter=0;
dem123456789 14:92bacb5af01b 20 char PC_message[256];
dem123456789 14:92bacb5af01b 21 int PC_message_counter=0;
dem123456789 11:1caacb994236 22
dem123456789 11:1caacb994236 23 string IMU_Y="N/A";
dem123456789 11:1caacb994236 24 string IMU_P="N/A";
dem123456789 11:1caacb994236 25 string IMU_R="N/A";
dem123456789 14:92bacb5af01b 26 string GPS_Quality="N/A";
dem123456789 11:1caacb994236 27 string GPS_UTC="N/A";
dem123456789 11:1caacb994236 28 string GPS_Latitude="N/A";
dem123456789 11:1caacb994236 29 string GPS_Longtitude="N/A";
dem123456789 11:1caacb994236 30 string GPS_Altitude="N/A";
dem123456789 22:faba67585854 31 string GPS_Altitude_Unit="N/A";
dem123456789 11:1caacb994236 32 string GPS_Num_Satellite="N/A";
dem123456789 11:1caacb994236 33 string GPS_HDOP="N/A";
dem123456789 12:8644abfa86da 34 string GPS_VDOP="N/A";
dem123456789 12:8644abfa86da 35 string GPS_PDOP="N/A";
dem123456789 14:92bacb5af01b 36 string GPS_Date="N/A";
dem123456789 14:92bacb5af01b 37 string GPS_VelocityKnot="N/A";
dem123456789 22:faba67585854 38 string GPS_VelocityKnot_Unit="N/A";
dem123456789 14:92bacb5af01b 39 string GPS_VelocityKph="N/A";
dem123456789 22:faba67585854 40 string GPS_VelocityKph_Unit="N/A";
dem123456789 23:cc06a8226f72 41 string temp = "";
dem123456789 22:faba67585854 42
dem123456789 22:faba67585854 43 double D_IMU_Y=0;
dem123456789 22:faba67585854 44 double D_IMU_P=0;
dem123456789 22:faba67585854 45 double D_IMU_R=0;
dem123456789 22:faba67585854 46 double D_GPS_Quality=0;
dem123456789 22:faba67585854 47 double D_GPS_UTC=0;
dem123456789 22:faba67585854 48 double D_GPS_Latitude=0;
dem123456789 22:faba67585854 49 double D_GPS_Latitude_Direction=0;
dem123456789 22:faba67585854 50 double D_GPS_Longtitude=0;
dem123456789 22:faba67585854 51 double D_GPS_Longtitude_Direction=0;
dem123456789 22:faba67585854 52 double D_GPS_Altitude=0;
dem123456789 22:faba67585854 53 double D_GPS_Num_Satellite=0;
dem123456789 22:faba67585854 54 double D_GPS_HDOP=0;
dem123456789 22:faba67585854 55 double D_GPS_VDOP=0;
dem123456789 22:faba67585854 56 double D_GPS_PDOP=0;
dem123456789 22:faba67585854 57 double D_GPS_Date=0;
dem123456789 22:faba67585854 58 double D_GPS_VelocityKnot=0;
dem123456789 22:faba67585854 59 double D_GPS_VelocityKph=0;
dem123456789 14:92bacb5af01b 60
dem123456789 12:8644abfa86da 61 int asterisk_idx;
dem123456789 9:bf5939466e86 62
dem123456789 20:a820531c78bc 63 double Longtitude_Path[MAX_TASK_SIZE];
dem123456789 20:a820531c78bc 64 double Latitude_Path[MAX_TASK_SIZE];
dem123456789 20:a820531c78bc 65
taoqiuyang 26:353a80179346 66 double angle_to_path_point,distance_to_path_point,desired_speed;
taoqiuyang 26:353a80179346 67 double rudder_ctrl_parameters[3];
taoqiuyang 26:353a80179346 68 double rudder_variables[5];//,,,prev,out
taoqiuyang 26:353a80179346 69 double T=0.2; //controller update period=0.2sec, 5Hz
taoqiuyang 26:353a80179346 70
taoqiuyang 26:353a80179346 71
dem123456789 9:bf5939466e86 72 vector<string> split(const string &s, char delim) {
dem123456789 9:bf5939466e86 73 stringstream ss(s);
dem123456789 9:bf5939466e86 74 string item;
dem123456789 9:bf5939466e86 75 vector<string> tokens;
dem123456789 9:bf5939466e86 76 while (getline(ss, item, delim)) {
dem123456789 15:dbf20c1209ae 77 if (item.empty()) {
dem123456789 20:a820531c78bc 78 item = "N/A";
dem123456789 15:dbf20c1209ae 79 }
dem123456789 9:bf5939466e86 80 tokens.push_back(item);
dem123456789 9:bf5939466e86 81 }
dem123456789 9:bf5939466e86 82 return tokens;
dem123456789 9:bf5939466e86 83 }
dem123456789 9:bf5939466e86 84
dem123456789 9:bf5939466e86 85 void updateIMU(string IMU_data) {
dem123456789 9:bf5939466e86 86 string IMU_data_string(IMU_data);
dem123456789 9:bf5939466e86 87 if (IMU_data_string.substr(0,4) == "#YPR" and IMU_data_string.size() <= MAX_IMU_SIZE) {
dem123456789 9:bf5939466e86 88 IMU_data_string = IMU_data_string.substr(5);
dem123456789 9:bf5939466e86 89 vector<string> result = split(IMU_data_string, ',');
dem123456789 9:bf5939466e86 90 IMU_Y = result.at(0);
dem123456789 23:cc06a8226f72 91 D_IMU_Y = strtod(IMU_Y.c_str(), NULL);
dem123456789 9:bf5939466e86 92 IMU_P = result.at(1);
dem123456789 23:cc06a8226f72 93 D_IMU_P = strtod(IMU_P.c_str(), NULL);
dem123456789 15:dbf20c1209ae 94 IMU_R = result.at(2).substr(0, result.at(2).size()-1);
dem123456789 23:cc06a8226f72 95 D_IMU_R = strtod(IMU_R.c_str(), NULL);
dem123456789 9:bf5939466e86 96 }
dem123456789 9:bf5939466e86 97 }
dem123456789 9:bf5939466e86 98
dem123456789 10:12ba6ed2d6f0 99 void updateGPS(string GPS_data) {
dem123456789 10:12ba6ed2d6f0 100 string GPS_data_string(GPS_data);
dem123456789 11:1caacb994236 101 if (GPS_data_string.substr(0,6) == "$GPGGA") {
dem123456789 11:1caacb994236 102 GPS_data_string = GPS_data_string.substr(7);
dem123456789 10:12ba6ed2d6f0 103 vector<string> result = split(GPS_data_string, ',');
dem123456789 14:92bacb5af01b 104 GPS_Quality = result.at(5);
dem123456789 22:faba67585854 105 D_GPS_Quality = strtod(result.at(5).c_str(), NULL);
dem123456789 14:92bacb5af01b 106 if(GPS_Quality != "0" and GPS_Quality != "6") {
dem123456789 11:1caacb994236 107 GPS_UTC = result.at(0);
dem123456789 23:cc06a8226f72 108 D_GPS_UTC = strtod(GPS_UTC.c_str(), NULL);
dem123456789 23:cc06a8226f72 109 GPS_Latitude = result.at(1) + result.at(2);
dem123456789 23:cc06a8226f72 110 temp = result.at(1);
dem123456789 23:cc06a8226f72 111 if (temp[0] == '0') {
dem123456789 23:cc06a8226f72 112 temp[0] = '-';
dem123456789 23:cc06a8226f72 113 }
dem123456789 23:cc06a8226f72 114 D_GPS_Latitude = strtod(temp.c_str(), NULL);
dem123456789 23:cc06a8226f72 115 if (result.at(2) == "N") { // 0 means North
dem123456789 22:faba67585854 116 D_GPS_Latitude_Direction = 0;
dem123456789 23:cc06a8226f72 117 } else if (result.at(2) == "S") { // 1 means South
dem123456789 22:faba67585854 118 D_GPS_Latitude_Direction = 1;
dem123456789 22:faba67585854 119 }
dem123456789 23:cc06a8226f72 120 GPS_Longtitude = result.at(3) + result.at(4);
dem123456789 23:cc06a8226f72 121 temp = result.at(3);
dem123456789 23:cc06a8226f72 122 if (temp[0] == '0') {
dem123456789 23:cc06a8226f72 123 temp[0] = '-';
dem123456789 23:cc06a8226f72 124 }
dem123456789 23:cc06a8226f72 125 D_GPS_Longtitude = strtod(temp.c_str(), NULL);
dem123456789 23:cc06a8226f72 126 if (result.at(4) == "E") { // 0 means East
dem123456789 23:cc06a8226f72 127 D_GPS_Longtitude_Direction = 0;
dem123456789 23:cc06a8226f72 128 } else if (result.at(4) == "W") { // 1 means West
dem123456789 23:cc06a8226f72 129 D_GPS_Longtitude_Direction = 1;
dem123456789 22:faba67585854 130 }
dem123456789 11:1caacb994236 131 GPS_Num_Satellite = result.at(6);
dem123456789 22:faba67585854 132 D_GPS_Num_Satellite = strtod(result.at(6).c_str(), NULL);
dem123456789 11:1caacb994236 133 GPS_HDOP = result.at(7);
dem123456789 22:faba67585854 134 D_GPS_HDOP = strtod(result.at(7).c_str(), NULL);
dem123456789 11:1caacb994236 135 GPS_Altitude = result.at(8) + result.at(9);
dem123456789 22:faba67585854 136 D_GPS_Altitude = strtod(result.at(8).c_str(), NULL);
dem123456789 22:faba67585854 137 GPS_Altitude_Unit = result.at(9);
dem123456789 11:1caacb994236 138 }
dem123456789 14:92bacb5af01b 139 } else if (GPS_data_string.substr(0,6) == "$GPGSA" and GPS_Quality != "0" and GPS_Quality != "6") {
dem123456789 12:8644abfa86da 140 GPS_data_string = GPS_data_string.substr(7);
dem123456789 12:8644abfa86da 141 vector<string> result = split(GPS_data_string, ',');
dem123456789 12:8644abfa86da 142 GPS_PDOP = result.at(14);
dem123456789 22:faba67585854 143 D_GPS_PDOP = strtod(result.at(14).c_str(), NULL);
dem123456789 12:8644abfa86da 144 asterisk_idx = result.at(16).find('*');
dem123456789 12:8644abfa86da 145 GPS_VDOP = result.at(16).substr(0, asterisk_idx);
dem123456789 22:faba67585854 146 D_GPS_VDOP = strtod(result.at(16).substr(0, asterisk_idx).c_str(), NULL);
dem123456789 14:92bacb5af01b 147 } else if (GPS_data_string.substr(0,6) == "$GPRMC" and GPS_Quality != "0" and GPS_Quality != "6") {
dem123456789 12:8644abfa86da 148 GPS_data_string = GPS_data_string.substr(7);
dem123456789 12:8644abfa86da 149 vector<string> result = split(GPS_data_string, ',');
dem123456789 14:92bacb5af01b 150 GPS_Date = result.at(8);
dem123456789 22:faba67585854 151 D_GPS_Date = strtod(result.at(8).c_str(), NULL);
dem123456789 14:92bacb5af01b 152 } else if (GPS_data_string.substr(0,6) == "$GPVTG" and GPS_Quality != "0" and GPS_Quality != "6") {
dem123456789 12:8644abfa86da 153 GPS_data_string = GPS_data_string.substr(7);
dem123456789 12:8644abfa86da 154 vector<string> result = split(GPS_data_string, ',');
dem123456789 14:92bacb5af01b 155 GPS_VelocityKnot = result.at(4) + result.at(5);
dem123456789 22:faba67585854 156 D_GPS_VelocityKnot = strtod(result.at(4).c_str(), NULL);
dem123456789 22:faba67585854 157 GPS_VelocityKnot_Unit = result.at(5);
dem123456789 12:8644abfa86da 158 asterisk_idx = result.at(7).find('*');
dem123456789 14:92bacb5af01b 159 GPS_VelocityKph = result.at(6) + result.at(7).substr(0, asterisk_idx);
dem123456789 22:faba67585854 160 D_GPS_VelocityKph = strtod(result.at(6).c_str(), NULL);
dem123456789 22:faba67585854 161 GPS_VelocityKph_Unit = result.at(7).substr(0, asterisk_idx);
dem123456789 10:12ba6ed2d6f0 162 }
dem123456789 12:8644abfa86da 163
dem123456789 10:12ba6ed2d6f0 164 }
dem123456789 16:0ea992d9a390 165 /* Get data from SailBoat
dem123456789 16:0ea992d9a390 166 @GET=parameter
dem123456789 16:0ea992d9a390 167 Ex: @GET=GPS_Quality
dem123456789 16:0ea992d9a390 168 Supported parameter: GPS_Quality, GPS_UTC, GPS_Latitude, GPS_Longtitude, GPS_Altitude,
dem123456789 16:0ea992d9a390 169 GPS_Num_Satellite, GPS_HDOP, GPS_VDOP, GPS_PDOP, GPS_Date, GPS_VelocityKnot, GPS_VelocityKph
dem123456789 16:0ea992d9a390 170 Set path to SailBoat
dem123456789 20:a820531c78bc 171 @SET=PATH, Latitude, Longtitude, Task id
dem123456789 20:a820531c78bc 172 @SET=PATH, 33.776318, -84.407590, 3
dem123456789 16:0ea992d9a390 173 */
dem123456789 15:dbf20c1209ae 174 void decodePC(string PC_data) {
dem123456789 15:dbf20c1209ae 175 string PC_data_string(PC_data);
dem123456789 15:dbf20c1209ae 176 if (PC_data_string.substr(0,4) == "@GET") {
dem123456789 15:dbf20c1209ae 177 pc.printf("%s", PC_data_string.c_str());
dem123456789 15:dbf20c1209ae 178 PC_data_string = PC_data_string.substr(5, PC_data_string.size()-6);
dem123456789 20:a820531c78bc 179 pc.printf("%s\n", decodeCommandGET(PC_data_string).c_str());
dem123456789 16:0ea992d9a390 180 } else if (PC_data_string.substr(0,4) == "@SET") {
dem123456789 20:a820531c78bc 181 pc.printf("%s", PC_data_string.c_str());
dem123456789 20:a820531c78bc 182 PC_data_string = PC_data_string.substr(5, PC_data_string.size()-6);
dem123456789 20:a820531c78bc 183 string claim = decodeCommandSET(PC_data_string);
dem123456789 20:a820531c78bc 184 if (claim == "DONE") {
dem123456789 20:a820531c78bc 185 pc.printf("Current Path: Longtitude, Latitude\n");
dem123456789 20:a820531c78bc 186 for (int i=0;i<MAX_TASK_SIZE;++i) {
dem123456789 20:a820531c78bc 187 pc.printf(" %f, %f\n", Longtitude_Path[i], Latitude_Path[i]);
dem123456789 20:a820531c78bc 188 }
dem123456789 20:a820531c78bc 189 }
dem123456789 20:a820531c78bc 190 pc.printf("%s\n", claim.c_str());
dem123456789 16:0ea992d9a390 191 }
dem123456789 15:dbf20c1209ae 192 }
dem123456789 15:dbf20c1209ae 193
dem123456789 15:dbf20c1209ae 194
taoqiuyang 24:8e38cc14150c 195
dem123456789 11:1caacb994236 196 void printStateIMU() {
dem123456789 23:cc06a8226f72 197 //pc.printf("IMU_Y: %s, IMU_P: %s, IMU_R: %s\n",IMU_Y.c_str(), IMU_P.c_str(), IMU_R.c_str());
dem123456789 23:cc06a8226f72 198 pc.printf("D_IMU_Y: %f, D_IMU_P: %f, D_IMU_R: %f\n",D_IMU_Y, D_IMU_P, D_IMU_R);
dem123456789 11:1caacb994236 199 }
dem123456789 11:1caacb994236 200
dem123456789 12:8644abfa86da 201 void printStateGPS() {
dem123456789 23:cc06a8226f72 202 /*
dem123456789 14:92bacb5af01b 203 pc.printf("GPS_Quality: %s, GPS_UTC: %s, GPS_Latitude: %s, GPS_Longtitude: %s, GPS_Altitude: %s, "
dem123456789 14:92bacb5af01b 204 "GPS_Num_Satellite: %s, GPS_HDOP: %s, GPS_VDOP: %s, GPS_PDOP: %s, GPS_Date: %s, GPS_VelocityKnot: %s, GPS_VelocityKph: %s\n",
dem123456789 14:92bacb5af01b 205 GPS_Quality.c_str(), GPS_UTC.c_str(), GPS_Latitude.c_str(), GPS_Longtitude.c_str(), GPS_Altitude.c_str(), GPS_Num_Satellite.c_str(),
dem123456789 23:cc06a8226f72 206 GPS_HDOP.c_str(), GPS_VDOP.c_str(), GPS_PDOP.c_str(), GPS_Date.c_str(), GPS_VelocityKnot.c_str(), GPS_VelocityKph.c_str());
dem123456789 23:cc06a8226f72 207 */
dem123456789 23:cc06a8226f72 208
dem123456789 23:cc06a8226f72 209 pc.printf("D_GPS_Quality: %f, D_GPS_UTC: %f, D_GPS_Latitude: %f, D_GPS_Latitude_Direction: %f, D_GPS_Longtitude: %f, D_GPS_Longtitude_Direction: %f, D_GPS_Altitude: %f,\n"
dem123456789 23:cc06a8226f72 210 "D_GPS_Num_Satellite: %f, D_GPS_HDOP: %f, D_GPS_VDOP: %f, D_GPS_PDOP: %f, D_GPS_Date: %f, D_GPS_VelocityKnot: %f, D_GPS_VelocityKph: %f\n",
dem123456789 23:cc06a8226f72 211 D_GPS_Quality, D_GPS_UTC, D_GPS_Latitude, D_GPS_Latitude_Direction, D_GPS_Longtitude, D_GPS_Longtitude_Direction, D_GPS_Altitude, D_GPS_Num_Satellite,
dem123456789 23:cc06a8226f72 212 D_GPS_HDOP, D_GPS_VDOP, D_GPS_PDOP, D_GPS_Date, D_GPS_VelocityKnot, D_GPS_VelocityKph);
dem123456789 23:cc06a8226f72 213
dem123456789 12:8644abfa86da 214 }
dem123456789 14:92bacb5af01b 215
dem123456789 11:1caacb994236 216 //#YPR=-183.74,-134.27,-114.39
taoqiuyang 4:37d118f2348c 217 void IMU_serial_ISR() {
taoqiuyang 3:ab9f94d112c0 218 char buf;
taoqiuyang 3:ab9f94d112c0 219
taoqiuyang 3:ab9f94d112c0 220 while (IMU.readable()) {
taoqiuyang 3:ab9f94d112c0 221 buf = IMU.getc();
taoqiuyang 3:ab9f94d112c0 222
dem123456789 14:92bacb5af01b 223 //pc.putc(buf);
taoqiuyang 3:ab9f94d112c0 224 IMU_message[IMU_message_counter]=buf;
dem123456789 9:bf5939466e86 225 IMU_message_counter+=1;
taoqiuyang 3:ab9f94d112c0 226
taoqiuyang 3:ab9f94d112c0 227 if (buf=='\n'){
dem123456789 9:bf5939466e86 228 string IMU_copy(IMU_message, IMU_message_counter);
dem123456789 11:1caacb994236 229 //pc.printf("%s", IMU_copy.c_str());
dem123456789 9:bf5939466e86 230 updateIMU(IMU_copy);
dem123456789 9:bf5939466e86 231 IMU_message_counter=0;
dem123456789 9:bf5939466e86 232 IMU_copy[0] = '\0';
dem123456789 9:bf5939466e86 233 }
dem123456789 9:bf5939466e86 234
taoqiuyang 3:ab9f94d112c0 235 }
taoqiuyang 2:afb333543af5 236 led2 = !led2;
taoqiuyang 2:afb333543af5 237 }
dem123456789 9:bf5939466e86 238
dem123456789 9:bf5939466e86 239
dem123456789 8:1f5a44bade4d 240
taoqiuyang 5:451b8203ef99 241 void GPS_serial_ISR() {
taoqiuyang 5:451b8203ef99 242 char buf;
taoqiuyang 5:451b8203ef99 243
taoqiuyang 5:451b8203ef99 244 while (GPS.readable()) {
taoqiuyang 5:451b8203ef99 245 buf = GPS.getc();
dem123456789 14:92bacb5af01b 246
dem123456789 14:92bacb5af01b 247 //pc.putc(buf);
dem123456789 10:12ba6ed2d6f0 248 GPS_message[GPS_message_counter]=buf;
dem123456789 10:12ba6ed2d6f0 249 GPS_message_counter+=1;
dem123456789 10:12ba6ed2d6f0 250
dem123456789 10:12ba6ed2d6f0 251 if (buf=='\n'){
dem123456789 10:12ba6ed2d6f0 252 string GPS_copy(GPS_message, GPS_message_counter);
dem123456789 11:1caacb994236 253 //pc.printf("%s", GPS_copy.c_str());
dem123456789 10:12ba6ed2d6f0 254 updateGPS(GPS_copy);
dem123456789 10:12ba6ed2d6f0 255 GPS_message_counter=0;
dem123456789 10:12ba6ed2d6f0 256 GPS_copy[0] = '\0';
dem123456789 10:12ba6ed2d6f0 257 }
taoqiuyang 5:451b8203ef99 258 }
taoqiuyang 5:451b8203ef99 259
taoqiuyang 5:451b8203ef99 260 led3 = !led3;
taoqiuyang 5:451b8203ef99 261 }
taoqiuyang 3:ab9f94d112c0 262
dem123456789 8:1f5a44bade4d 263 void PC_serial_ISR() {
dem123456789 8:1f5a44bade4d 264 char buf;
dem123456789 8:1f5a44bade4d 265
dem123456789 8:1f5a44bade4d 266 while (pc.readable()) {
dem123456789 8:1f5a44bade4d 267 buf = pc.getc();
dem123456789 14:92bacb5af01b 268
dem123456789 14:92bacb5af01b 269 //pc.putc(buf);
dem123456789 14:92bacb5af01b 270 PC_message[PC_message_counter]=buf;
dem123456789 14:92bacb5af01b 271 PC_message_counter+=1;
dem123456789 14:92bacb5af01b 272
dem123456789 14:92bacb5af01b 273 if (buf=='\n'){
dem123456789 14:92bacb5af01b 274 string PC_copy(PC_message, PC_message_counter);
dem123456789 14:92bacb5af01b 275 //pc.printf("%s", PC_copy.c_str());
dem123456789 14:92bacb5af01b 276 decodePC(PC_copy);
dem123456789 14:92bacb5af01b 277 PC_message_counter=0;
dem123456789 14:92bacb5af01b 278 PC_copy[0] = '\0';
dem123456789 14:92bacb5af01b 279 }
dem123456789 8:1f5a44bade4d 280 }
dem123456789 8:1f5a44bade4d 281
dem123456789 8:1f5a44bade4d 282 led4= !led4;
dem123456789 8:1f5a44bade4d 283 }
dem123456789 21:99be83550601 284
taoqiuyang 24:8e38cc14150c 285
dem123456789 21:99be83550601 286 void set_servo_position(Servo targetServo, float angleDeg, float minDeg, float minNorVal, float maxDeg, float maxNorVal){
dem123456789 21:99be83550601 287 /*angleDeg: desired angle
dem123456789 21:99be83550601 288 minDeg: minimum angle in degrees
dem123456789 21:99be83550601 289 minNorVal: normalized value[0,1] when servo is at its minimum angle
dem123456789 21:99be83550601 290 maxDeg: maximum angle in degrees
dem123456789 21:99be83550601 291 maxNorVal: normalized value[0,1] when servo is at its maximum angle
dem123456789 21:99be83550601 292 */
dem123456789 21:99be83550601 293
dem123456789 21:99be83550601 294 float pos; //normalized angle, [0,1]
dem123456789 21:99be83550601 295 float scale; //scale factor for servo calibration
dem123456789 21:99be83550601 296
dem123456789 21:99be83550601 297 //extreme conditions
dem123456789 21:99be83550601 298 if (angleDeg<minDeg){
dem123456789 21:99be83550601 299 pos=minNorVal;
dem123456789 21:99be83550601 300 }
dem123456789 21:99be83550601 301 if (angleDeg>maxDeg){
dem123456789 21:99be83550601 302 pos=maxNorVal;
dem123456789 21:99be83550601 303 }
dem123456789 21:99be83550601 304
dem123456789 21:99be83550601 305 //Calculate scale factor for servo calibration
dem123456789 21:99be83550601 306 scale = (angleDeg-minDeg)/(maxDeg-minDeg);
dem123456789 21:99be83550601 307 //Calculate servo normalized value
dem123456789 21:99be83550601 308 pos = minNorVal + scale*(maxNorVal-minNorVal);
dem123456789 21:99be83550601 309
dem123456789 21:99be83550601 310 //send signal to servo
dem123456789 21:99be83550601 311 targetServo=pos;
dem123456789 21:99be83550601 312 }
dem123456789 21:99be83550601 313
taoqiuyang 26:353a80179346 314
taoqiuyang 26:353a80179346 315 void initialize_controller(){
taoqiuyang 26:353a80179346 316 rudder_variables[0]=0;
taoqiuyang 26:353a80179346 317 rudder_variables[1]=0;
taoqiuyang 26:353a80179346 318 rudder_variables[2]=0;
taoqiuyang 26:353a80179346 319 rudder_variables[3]=0;
taoqiuyang 26:353a80179346 320 rudder_variables[4]=0;
taoqiuyang 26:353a80179346 321 rudder_ctrl_parameters[0]=1;
taoqiuyang 26:353a80179346 322 rudder_ctrl_parameters[1]=0;
taoqiuyang 26:353a80179346 323 rudder_ctrl_parameters[2]=0;
taoqiuyang 26:353a80179346 324 }
taoqiuyang 26:353a80179346 325
taoqiuyang 26:353a80179346 326 void update_controller_tmr_ISR() {
taoqiuyang 26:353a80179346 327 /*Input: angle(deg) difference between heading from IMU and path point航向与目的点之间的夹角
taoqiuyang 26:353a80179346 328 distance(meter) to the next path point
taoqiuyang 26:353a80179346 329 Global Variables: angle_to_path_point,distance_to_path_point;
taoqiuyang 26:353a80179346 330
taoqiuyang 26:353a80179346 331 Function: drive two servos to navigate the sailboat to the desired path point
taoqiuyang 26:353a80179346 332 */
taoqiuyang 26:353a80179346 333
taoqiuyang 26:353a80179346 334 rudder_variables[0]=rudder_ctrl_parameters[0]*angle_to_path_point;
taoqiuyang 26:353a80179346 335 rudder_variables[1]=rudder_variables[1]+rudder_ctrl_parameters[1]*angle_to_path_point*T;
taoqiuyang 26:353a80179346 336 rudder_variables[2]=(rudder_variables[3]-angle_to_path_point)/T;
taoqiuyang 26:353a80179346 337 rudder_variables[3]=angle_to_path_point;
taoqiuyang 26:353a80179346 338 rudder_variables[4]=rudder_variables[0]+rudder_variables[1]+rudder_variables[2];
taoqiuyang 26:353a80179346 339
taoqiuyang 26:353a80179346 340
taoqiuyang 26:353a80179346 341 //Drive servos
taoqiuyang 26:353a80179346 342 set_servo_position(rudderServo,rudder_variables[4],-45,0,45,1);
taoqiuyang 26:353a80179346 343 }
taoqiuyang 26:353a80179346 344
taoqiuyang 26:353a80179346 345
taoqiuyang 26:353a80179346 346
dem123456789 21:99be83550601 347 int log_data_SD(){
dem123456789 21:99be83550601 348 FILE *fp = fopen("/sd/dataLog/dataLog.txt", "w");
dem123456789 21:99be83550601 349 if(fp == NULL) {
dem123456789 21:99be83550601 350 return 0;
dem123456789 21:99be83550601 351 }else{
dem123456789 21:99be83550601 352 //Write all the useful data to the SD card
dem123456789 21:99be83550601 353 fprintf(fp, "Nya Pass~");
dem123456789 21:99be83550601 354 fclose(fp);
dem123456789 21:99be83550601 355 return 1;
dem123456789 21:99be83550601 356 }
dem123456789 21:99be83550601 357 }
dem123456789 21:99be83550601 358
dem123456789 21:99be83550601 359
taoqiuyang 0:f4d390c06705 360 int main() {
taoqiuyang 2:afb333543af5 361 IMU.baud(57600);
taoqiuyang 4:37d118f2348c 362 IMU.attach(&IMU_serial_ISR);
taoqiuyang 5:451b8203ef99 363 GPS.baud(38400);
taoqiuyang 5:451b8203ef99 364 GPS.attach(&GPS_serial_ISR);
dem123456789 8:1f5a44bade4d 365 pc.baud(115200);
dem123456789 8:1f5a44bade4d 366 pc.attach(&PC_serial_ISR);
taoqiuyang 26:353a80179346 367 ctrl_updt_timer.attach(&update_controller_tmr_ISR, T); // Update controller at 1/T Hz
taoqiuyang 26:353a80179346 368
taoqiuyang 26:353a80179346 369 initialize_controller();
taoqiuyang 1:e7245ffb4820 370
dem123456789 23:cc06a8226f72 371 //float angle=20;
taoqiuyang 2:afb333543af5 372 while (1) {
dem123456789 23:cc06a8226f72 373 // if (angle>160){angle=20;}
dem123456789 23:cc06a8226f72 374 // set_servo_position(rudderServo, angle, 0, 0, 180, 1);
dem123456789 23:cc06a8226f72 375 // set_servo_position(wingServo, angle, 0, 0, 180, 1);
dem123456789 23:cc06a8226f72 376 // angle=angle+10;
taoqiuyang 26:353a80179346 377
taoqiuyang 26:353a80179346 378
dem123456789 15:dbf20c1209ae 379 wait(0.4);
dem123456789 23:cc06a8226f72 380 printStateIMU();
dem123456789 23:cc06a8226f72 381 printStateGPS();
dem123456789 21:99be83550601 382 led1 = !led1;
taoqiuyang 0:f4d390c06705 383 }
taoqiuyang 0:f4d390c06705 384 }