2011-02-13 20:43:11 -04:00
|
|
|
/*
|
2012-08-17 03:21:25 -03:00
|
|
|
* Example of DataFlash library.
|
|
|
|
* Code by Jordi MuÒoz and Jose Julio. DIYDrones.com
|
|
|
|
*/
|
2011-02-13 20:43:11 -04:00
|
|
|
|
2011-07-19 20:00:18 -03:00
|
|
|
// Libraries
|
2012-10-04 10:46:35 -03:00
|
|
|
#include <FastSerial.h>
|
|
|
|
#include <AP_Common.h>
|
|
|
|
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
2012-08-17 03:21:25 -03:00
|
|
|
#include <SPI.h> // Arduino SPI lib
|
2012-10-09 15:39:09 -03:00
|
|
|
#include <AP_Semaphore.h> // Required by DataFlash library
|
2011-02-13 20:43:11 -04:00
|
|
|
#include <DataFlash.h>
|
|
|
|
|
2012-10-04 10:46:35 -03:00
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
// Serial ports
|
|
|
|
////////////////////////////////////////////////////////////////////////////////
|
|
|
|
//
|
|
|
|
// Note that FastSerial port buffers are allocated at ::begin time,
|
|
|
|
// so there is not much of a penalty to defining ports that we don't
|
|
|
|
// use.
|
|
|
|
//
|
|
|
|
FastSerialPort0(Serial); // FTDI/console
|
|
|
|
|
2011-02-13 20:43:11 -04:00
|
|
|
#define HEAD_BYTE1 0xA3
|
|
|
|
#define HEAD_BYTE2 0x95
|
|
|
|
|
2012-01-09 00:26:56 -04:00
|
|
|
// NOTE: You must uncomment one of the following two lines
|
2012-08-17 03:21:25 -03:00
|
|
|
DataFlash_APM2 DataFlash; // Uncomment this line if using APM2 hardware
|
2012-01-09 00:26:56 -04:00
|
|
|
//DataFlash_APM1 DataFlash; // Uncomment this line if using APM1 hardware
|
|
|
|
|
|
|
|
|
2011-02-13 20:43:11 -04:00
|
|
|
void setup()
|
|
|
|
{
|
2012-08-17 03:21:25 -03:00
|
|
|
Serial.begin(115200);
|
|
|
|
DataFlash.Init(); // DataFlash initialization
|
|
|
|
|
|
|
|
Serial.println("Dataflash Log Test 1.0");
|
|
|
|
|
|
|
|
// Test
|
|
|
|
delay(20);
|
|
|
|
DataFlash.ReadManufacturerID();
|
|
|
|
delay(10);
|
|
|
|
Serial.print("Manufacturer:");
|
|
|
|
Serial.print(int(DataFlash.df_manufacturer));
|
|
|
|
Serial.print(",");
|
|
|
|
Serial.print(DataFlash.df_device);
|
|
|
|
Serial.println();
|
|
|
|
|
|
|
|
// We start to write some info (sequentialy) starting from page 1
|
|
|
|
// This is similar to what we will do...
|
|
|
|
DataFlash.StartWrite(1);
|
|
|
|
Serial.println("After testing perform erase before using DataFlash for logging!");
|
|
|
|
Serial.println("");
|
|
|
|
Serial.println("Writing to flash... wait...");
|
|
|
|
for (int i = 0; i < 1000; i++) { // Write 1000 packets...
|
|
|
|
// We write packets of binary data... (without worry about nothing more)
|
|
|
|
DataFlash.WriteByte(HEAD_BYTE1);
|
|
|
|
DataFlash.WriteByte(HEAD_BYTE2);
|
|
|
|
DataFlash.WriteInt(2000 + i);
|
|
|
|
DataFlash.WriteInt(2001 + i);
|
|
|
|
DataFlash.WriteInt(2002 + i);
|
|
|
|
DataFlash.WriteInt(2003 + i);
|
|
|
|
DataFlash.WriteLong((long)i * 5000);
|
|
|
|
DataFlash.WriteLong((long)i * 16268);
|
|
|
|
DataFlash.WriteByte(0xA2); // 2 bytes of checksum (example)
|
|
|
|
DataFlash.WriteByte(0x4E);
|
|
|
|
delay(10);
|
|
|
|
}
|
|
|
|
delay(100);
|
2011-02-13 20:43:11 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
void loop()
|
|
|
|
{
|
2012-08-17 03:21:25 -03:00
|
|
|
int i, tmp_int;
|
|
|
|
byte tmp_byte1, tmp_byte2;
|
|
|
|
long tmp_long;
|
|
|
|
|
|
|
|
Serial.println("Start reading page 1...");
|
|
|
|
|
|
|
|
DataFlash.StartRead(1); // We start reading from page 1
|
|
|
|
|
|
|
|
for (i = 0; i < 200; i++) { // Read 200 packets...
|
|
|
|
|
|
|
|
tmp_byte1 = DataFlash.ReadByte();
|
|
|
|
tmp_byte2 = DataFlash.ReadByte();
|
|
|
|
|
|
|
|
Serial.print("PACKET:");
|
|
|
|
|
|
|
|
if ((tmp_byte1 == HEAD_BYTE1) && (tmp_byte1 == HEAD_BYTE1)) {
|
|
|
|
// Read 4 ints...
|
|
|
|
tmp_int = DataFlash.ReadInt();
|
|
|
|
Serial.print(tmp_int);
|
|
|
|
Serial.print(",");
|
|
|
|
tmp_int = DataFlash.ReadInt();
|
|
|
|
Serial.print(tmp_int);
|
|
|
|
Serial.print(",");
|
|
|
|
tmp_int = DataFlash.ReadInt();
|
|
|
|
Serial.print(tmp_int);
|
|
|
|
Serial.print(",");
|
|
|
|
tmp_int = DataFlash.ReadInt();
|
|
|
|
Serial.print(tmp_int);
|
|
|
|
Serial.print(",");
|
|
|
|
|
|
|
|
// Read 2 longs...
|
|
|
|
tmp_long = DataFlash.ReadLong();
|
|
|
|
Serial.print(tmp_long);
|
|
|
|
Serial.print(",");
|
|
|
|
tmp_long = DataFlash.ReadLong();
|
|
|
|
Serial.print(tmp_long);
|
|
|
|
Serial.print(";");
|
|
|
|
|
|
|
|
// Read the checksum...
|
|
|
|
tmp_byte1 = DataFlash.ReadByte();
|
|
|
|
tmp_byte2 = DataFlash.ReadByte();
|
|
|
|
}
|
|
|
|
Serial.println();
|
|
|
|
}
|
|
|
|
Serial.println("");
|
|
|
|
Serial.println("Test complete. Test will repeat in 20 seconds");
|
|
|
|
Serial.println("");
|
|
|
|
delay(20000);
|
2010-05-28 11:38:51 -03:00
|
|
|
}
|