Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: MODGPS MODSERIAL SDFileSystem mbed
Revision 9:7dcfa24d5e7a, committed 2013-05-30
- Comitter:
- njewin
- Date:
- Thu May 30 13:32:54 2013 +0000
- Parent:
- 8:0ce247da6370
- Child:
- 10:d96e068f3595
- Commit message:
- Saved before compiling via macOS
Changed in this revision
| UM6_config/UM6_config.h | Show annotated file Show diff for this revision Revisions of this file |
| main.cpp | Show annotated file Show diff for this revision Revisions of this file |
--- a/UM6_config/UM6_config.h Mon May 27 17:22:36 2013 +0000
+++ b/UM6_config/UM6_config.h Thu May 30 13:32:54 2013 +0000
@@ -1,6 +1,6 @@
/* ------------------------------------------------------------------------------
File: UM6_config.h
- Author: CH Robotics, edited by Nathan Ewin
+ Author: CH Robotics, edited by LHiggs, & Nathan Ewin
Version: 1.0
Description: Preprocessor definitions and function declarations for UM6 configuration
@@ -142,10 +142,12 @@
float Roll;
float Pitch;
float Yaw;
-double GPS_long;
-double GPS_lat;
+float GPS_long;
+float GPS_lat;
float GPS_course;
float GPS_speed;
+int32_t GPS_lat_raw;
+
};
UM6 data;
@@ -166,8 +168,14 @@
int16_t MY_DATA_EULER_PHI;
int16_t MY_DATA_EULER_THETA;
int16_t MY_DATA_EULER_PSI;
-double MY_DATA_GPS_LONG;
-double MY_DATA_GPS_LAT;
+int32_t MY_DATA_GPS_LONG;
+int32_t MY_DATA_GPS_LONG0;
+int32_t MY_DATA_GPS_LONG1;
+int32_t MY_DATA_GPS_LONG2;
+int32_t MY_DATA_GPS_LAT;
+int32_t MY_DATA_GPS_LAT0;
+int32_t MY_DATA_GPS_LAT1;
+int32_t MY_DATA_GPS_LAT2;
int16_t MY_DATA_GPS_COURSE;
int16_t MY_DATA_GPS_SPEED;
@@ -476,16 +484,23 @@
// GPS long
if (new_packet.address == UM6_GPS_LONGITUDE) {
// Longitude
- MY_DATA_GPS_LONG = (int32_t)new_packet.packet_data;
- data.GPS_long = MY_DATA_GPS_LAT;
+ MY_DATA_GPS_LONG0 = (int32_t)new_packet.packet_data[0]<<24;
+ MY_DATA_GPS_LONG1 = (int32_t)new_packet.packet_data[1]<<16;
+ MY_DATA_GPS_LONG2 = (int32_t)new_packet.packet_data[2]<<8;
+ MY_DATA_GPS_LONG = MY_DATA_GPS_LONG0|MY_DATA_GPS_LONG1|MY_DATA_GPS_LONG2|new_packet.packet_data[3];
+ memcpy(&data.GPS_long,&MY_DATA_GPS_LONG,sizeof(int));
}
//------------------------------------------------------------
//-------------------------------------------------------------------
// GPS lat
if (new_packet.address == UM6_GPS_LATITUDE) {
// Latitude
- MY_DATA_GPS_LAT = (int32_t)new_packet.packet_data;
- data.GPS_lat = MY_DATA_GPS_LONG;
+ MY_DATA_GPS_LAT0 = (int32_t)new_packet.packet_data[0]<<24;
+ MY_DATA_GPS_LAT1 = (int32_t)new_packet.packet_data[1]<<16;
+ MY_DATA_GPS_LAT2 = (int32_t)new_packet.packet_data[2]<<8;
+ MY_DATA_GPS_LAT = MY_DATA_GPS_LAT0|MY_DATA_GPS_LAT1|MY_DATA_GPS_LAT2|new_packet.packet_data[3];
+ memcpy(&data.GPS_lat,&MY_DATA_GPS_LAT,sizeof(int));
+ data.GPS_lat_raw = MY_DATA_GPS_LAT;
}
//------------------------------------------------------------
} // end if(ADDRESS_TYPE_DATA)
@@ -524,4 +539,13 @@
Long -2.000001
Long -2.000001
Long -26815635079454453000000000000000000000000000000000000000000000000000000000000000000000000000000000000000000
+
+//code
+int32_t GPS_long;
+int32_t MY_DATA_GPS_LONG;
+MY_DATA_GPS_LONG = (int32_t)new_packet.packet_data;
+data.GPS_long = MY_DATA_GPS_LAT;
+//print out
+Long nan
+Long 0.000000
*/
\ No newline at end of file
--- a/main.cpp Mon May 27 17:22:36 2013 +0000
+++ b/main.cpp Thu May 30 13:32:54 2013 +0000
@@ -6,22 +6,17 @@
//------------ system and interface setup ----------------------------//
-//////////////////////////////////////LocalFileSystem local("local"); // sets up local file on mbed
MODSERIAL pc(USBTX, USBRX); // sets up serial connection to pc terminal
//------------ Hardware setup ----------------------------------------//
-DigitalOut pc_led(LED1); // LED1 = PC SERIAL
-DigitalOut uart_led(LED2); // LED2 = UM6 SERIAL
-DigitalOut log_led(LED3); // debug LED
-DigitalIn enable(p10); // enable signal for logging data to file
+DigitalOut pc_led(LED1); // LED1 = PC SERIAL
+DigitalOut uart_led(LED2); // LED2 = UM6 SERIAL
+DigitalOut log_led(LED3); // debug LED
+DigitalOut debug_led(LED4); // debug LED
+DigitalIn enable(p10); // enable logging pin
+DigitalOut sync(p11); // sychronization (with CAN logger) pin
SDFileSystem sd(p5, p6, p7, p8, "sd"); // the pinout on the mbed Cool Components workshop board
-
-//------------ variables setup ---------------------------------------//
-Ticker tick;
-Timer t;
-int flag=0;
-
// interupt function for processing uart messages --------------------//
void rxCallback(MODSERIAL_IRQ_INFO *q) {
if (um6_uart.rxBufferGetCount() >= MAX_PACKET_DATA) {
@@ -31,77 +26,100 @@
}
//------------ LogData interrupt function ----------------------------//
+int flag=0;
void LogData() {
- flag=1;
+ flag=1; //interrupt sets flag that causes variables to be logged
}
//============= Main Program =========================================//
int main() {
- pc.baud(115200); // baud rate to pc interface
+ pc.baud(115200); // baud rate to pc interface
um6_uart.baud(115200); // baud rate to um6 interface
-
- t.start(); // start log time
-
- //---- call interrupt functions -------------------------//
+ Ticker tick;
+ Timer t;
+
+ //---- call interrupt functions --------------------------//
um6_uart.attach(&rxCallback, MODSERIAL::RxIrq); // attach interupt function to uart
tick.attach(&LogData, 0.5); // attaches LogData function to 'tick' ticker interrupt every 0.5s
-
- //---------- setup sd card -----------------------------//
- mkdir("/sd/mydir", 0777);
- FILE *fp = fopen("/sd/mydir/log1.csv", "w");
- if(fp == NULL) {
- error("Could not open file for write\n");
- }
-//////////////////////////// FILE *fp = fopen("/local/log1.csv", "w");
- // print TEST signals to file, header
-// fprintf(fp,"time(s),Yaw(deg),Accel(m/s2),GPS Speed(m/s) \r");
- // print ALL signals to file, header
- fprintf(fp, "time(s),Yaw(deg),Roll(deg),Pitch(deg),GyroX(deg/s),GyroY(deg/s),GyroZ(deg/s),AccelX(g),AccelY(g),AccelZ(g),GPScourse(deg),GPSspeed(m/s),Latitude(deg),Longitude(deg) \r"); // sends header to file
-
+ t.start(); // start logging time
+
+ //---------- setup sd card directory------------------------------//
+ int FileNo = 0;
+ mkdir("/sd/log_data", 0777);
- //---- main while loop ----------------------------------//
- //--(interrupt sets flag that causes variables to be logged)
- while(1) {
- if(flag==1) {
- log_led=1; // turns on LED3 to indicate logging
- float time=t.read();
- float Yaw=data.Yaw;
- float Roll=data.Roll;
- float Pitch=data.Pitch;
- float GyroX=data.Gyro_Proc_X;
- float GyroY=data.Gyro_Proc_Y;
- float GyroZ=data.Gyro_Proc_Z;
- float AccelX=data.Accel_Proc_X;
- float AccelY=data.Accel_Proc_Y;
- float AccelZ=data.Accel_Proc_Z;
- double GPSlong=data.GPS_long; // currently I can get GPS longitude to out data
- double GPSlat=data.GPS_lat; // currently I can get GPS latitude to out data
- float GPScourse=data.GPS_course;
- float GPSspeed=data.GPS_speed;
-
- //----- print TEST signals to file -------------------//
- // fprintf(fp,"%.3f,%.2f,%.4f,%.2f \r",time,Yaw,AccelX,GPSspeed);
- pc.printf("time %.3f,Yaw %f, Speed %f, Lat %f, Long %f \n",time,Yaw,GPSspeed,GPSlat,GPSlong);
- // pc.printf("0x%08X, %f\n", *(int *)&GPSlong, GPSlong);
-
- //----- print ALL signals to file --------------------//
- fprintf(fp, "%3.3f, %3.1f,%3.1f,%3.1f, %3.2f,%3.2f,%3.2f, %3.4f,%3.4f,%3.4f, %3.1f,%3.2f,%f,%f\r",time,Yaw,Roll,Pitch,GyroX,GyroY,GyroZ,AccelX,AccelY,AccelZ,GPScourse,GPSspeed,GPSlat,GPSlong);
- flag=0; // recents LogData interrupt flag
- pc_led = !pc_led; // Lights LED1 when transmitting to PC screen
- } // end if(flag=1) loop
-
- if(enable==0) {
- break; // breaks while loop if enable switched off
+ //---- main while loop -------------------------------------------//
+ while(1) {
+ //---- Setup file on SD card ----------------------------//
+ printf("Opening sd card\n");
+ char buffer[50];
+ sprintf(buffer, "/sd/log_data/%i.csv", FileNo);
+ //****************************************************
+ // This is necessary for card to work when reconnected
+ // Initialise disk
+ sd.disk_initialize();
+ //****************************************************
+ // Open a file for write
+ FILE *fp = fopen(buffer, "w");
+ if(fp == NULL) {
+ error("Could not open file for write\n");
}
+ //--- print TEST signals to file, header
+ //fprintf(fp,"time(s),Yaw(deg),Accel(m/s2),GPS Speed(m/s) \r");
+ //--- print ALL signals to file, header
+ fprintf(fp, "time(s),Yaw(deg),Roll(deg),Pitch(deg),GyroX(deg/s),GyroY(deg/s),GyroZ(deg/s),AccelX(g),AccelY(g),AccelZ(g),GPScourse(deg),GPSspeed(m/s),Latitude(deg),Longitude(deg) \r"); // sends header to file
+
+ while (!pc.readable()) {
+ if(flag==1) {
+ log_led=1; // turns on LED3 to indicate logging
+ float time=t.read();
+ float Yaw=data.Yaw;
+ float Roll=data.Roll;
+ float Pitch=data.Pitch;
+ float GyroX=data.Gyro_Proc_X;
+ float GyroY=data.Gyro_Proc_Y;
+ float GyroZ=data.Gyro_Proc_Z;
+ float AccelX=data.Accel_Proc_X;
+ float AccelY=data.Accel_Proc_Y;
+ float AccelZ=data.Accel_Proc_Z;
+ float GPSlong=data.GPS_long; // currently not reading GPS longitude correctly
+ float GPSlat=data.GPS_lat; // currently not reading GPS latitude correctly
+ float GPScourse=data.GPS_course;
+ float GPSspeed=data.GPS_speed;
+ int32_t GPSlatR=data.GPS_lat_raw;
+
+ //----- print TEST signals----------------------------//
+ // fprintf(fp,"%.3f,%.2f,%.4f,%.2f \r",time,Yaw,AccelX,GPSspeed);
+ pc.printf("time %.3f,Yaw %f,Accel %f, Speed %f, Lat %f, Long %f, LatR %d \n",time,Yaw,AccelX,GPSspeed,GPSlat,GPSlong,GPSlatR);
+ //pc.printf("time %.3f,Yaw %f,Accel %f, Speed %f \n",time,Yaw,AccelX,GPSspeed);
+ // pc.printf("time %f,LongIn 0x%08X, LongOut %f\n",time,GPSlong,*(int *)&GPSlong);
+
+ //----- print ALL signals to file --------------------//
+ fprintf(fp, "%3.3f, %3.1f,%3.1f,%3.1f, %3.2f,%3.2f,%3.2f, %3.4f,%3.4f,%3.4f, %3.1f,%3.2f,%d,%f\r",time,Yaw,Roll,Pitch,GyroX,GyroY,GyroZ,AccelX,AccelY,AccelZ,GPScourse,GPSspeed,GPSlat,GPSlong);
+ flag=0; // reset LogData interrupt flag
+ pc_led = !pc_led; // Lights LED1 when transmitting to PC screen
+ } // end if(flag=1) loop
+
+ if(enable==0) {
+ break; // breaks while loop if enable switched off
+ }
+ } // end while(!pc.readable()) loop
+ pc.printf(" Done. \n"); // prints 'done when logging is finished/enable switched off
+ log_led=0; // turns off LED logging is finished/enable switched off
+ wait(0.5); // debug wait for pc.printf
+ fclose(fp); // closes log file
+ pc.getc(); // Clear character from buffer
+
+ while (!pc.readable()) { // Wait for a key press to restart logging
+ };
+ pc.getc(); // Clear character from buffer
+ FileNo++; // Increment file number
} // end while(1) loop
- pc.printf(" done. \n"); // prints 'done when logging is finished/enable switched off
- log_led=0; // turns off LED logging is finished/enable switched off
- wait(0.5); // debug wait for pc.printf
- fclose(fp); // closes log file
+
} // end main() program
-/* opening a file BEFORE calling interrupts OK
+/* DEUBBING NOTES
+ opening a file BEFORE calling interrupts OK
opening a file and print to it BEFORE calling interrupts NOT OK (stops rest of program)
open a (local) file and print to it AFTER calling interrupts NOT OK (stops rest of program)
open a (sd) file and print to it AFTER calling interrupts OK