GPS and IMU reading works

Dependencies:   mbed Servo SDFileSystem

/media/uploads/taoqiuyang/img_2352.jpg

Committer:
dem123456789
Date:
Thu Oct 29 00:42:07 2015 +0000
Revision:
39:ef1a8055d744
Parent:
38:528e410f2f7d
Child:
40:9537722d185e
python code configuration finished;

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