GPS and IMU reading works

Dependencies:   mbed Servo SDFileSystem

/media/uploads/taoqiuyang/img_2352.jpg

Committer:
dem123456789
Date:
Sat Sep 19 18:40:43 2015 +0000
Revision:
29:95b0320bf779
Parent:
28:ae857c247fbd
Child:
30:faf6e0f81a0c
angle done not tested

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