GPS and IMU reading works

Dependencies:   mbed Servo SDFileSystem

/media/uploads/taoqiuyang/img_2352.jpg

Committer:
dem123456789
Date:
Tue Oct 13 05:21:33 2015 +0000
Revision:
36:f04f4ed6aabb
Parent:
35:009cc4509a90
Child:
37:7a136279daf3
wireless config

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