DataFlash_test ported to AP_HAL

This commit is contained in:
Pat Hickey 2012-12-12 14:21:04 -08:00 committed by Andrew Tridgell
parent a28c614fbe
commit 308281f252
3 changed files with 47 additions and 49 deletions

View File

@ -4,54 +4,50 @@
*/
// Libraries
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Progmem.h>
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <SPI.h> // Arduino SPI lib
#include <AP_Semaphore.h> // Required by DataFlash library
#include <DataFlash.h>
////////////////////////////////////////////////////////////////////////////////
// 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
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#define HEAD_BYTE1 0xA3
#define HEAD_BYTE2 0x95
// NOTE: You must uncomment one of the following two lines
DataFlash_APM2 DataFlash; // Uncomment this line if using APM2 hardware
//DataFlash_APM1 DataFlash; // Uncomment this line if using APM1 hardware
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
DataFlash_APM2 DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
DataFlash_APM1 DataFlash;
#endif
void setup()
{
Serial.begin(115200);
DataFlash.Init(); // DataFlash initialization
Serial.println("Dataflash Log Test 1.0");
hal.console->println("Dataflash Log Test 1.0");
// Test
delay(20);
hal.scheduler->delay(20);
DataFlash.ReadManufacturerID();
delay(10);
Serial.print("Manufacturer:");
Serial.print(int(DataFlash.df_manufacturer));
Serial.print(",");
Serial.print(DataFlash.df_device);
Serial.println();
hal.scheduler->delay(10);
hal.console->print("Manufacturer:");
hal.console->print(int(DataFlash.df_manufacturer));
hal.console->print(",");
hal.console->print(DataFlash.df_device);
hal.console->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...");
hal.console->println("After testing perform erase before using DataFlash for logging!");
hal.console->println("");
hal.console->println("Writing to flash... wait...");
for (int i = 0; i < 40; i++) { // Write 1000 packets...
// We write packets of binary data... (without worry about nothing more)
DataFlash.WriteByte(HEAD_BYTE1);
@ -64,18 +60,18 @@ void setup()
DataFlash.WriteLong((long)i * 16268);
DataFlash.WriteByte(0xA2); // 2 bytes of checksum (example)
DataFlash.WriteByte(0x4E);
delay(10);
hal.scheduler->delay(10);
}
delay(100);
hal.scheduler->delay(100);
}
void loop()
{
int i, tmp_int;
byte tmp_byte1, tmp_byte2;
uint8_t tmp_byte1, tmp_byte2;
long tmp_long;
Serial.println("Start reading page 1...");
hal.console->println("Start reading page 1...");
DataFlash.StartRead(1); // We start reading from page 1
@ -84,39 +80,41 @@ void loop()
tmp_byte1 = DataFlash.ReadByte();
tmp_byte2 = DataFlash.ReadByte();
Serial.print("PACKET:");
hal.console->print("PACKET:");
if ((tmp_byte1 == HEAD_BYTE1) && (tmp_byte1 == HEAD_BYTE1)) {
// Read 4 ints...
tmp_int = DataFlash.ReadInt();
Serial.print(tmp_int);
Serial.print(",");
hal.console->print(tmp_int);
hal.console->print(",");
tmp_int = DataFlash.ReadInt();
Serial.print(tmp_int);
Serial.print(",");
hal.console->print(tmp_int);
hal.console->print(",");
tmp_int = DataFlash.ReadInt();
Serial.print(tmp_int);
Serial.print(",");
hal.console->print(tmp_int);
hal.console->print(",");
tmp_int = DataFlash.ReadInt();
Serial.print(tmp_int);
Serial.print(",");
hal.console->print(tmp_int);
hal.console->print(",");
// Read 2 longs...
tmp_long = DataFlash.ReadLong();
Serial.print(tmp_long);
Serial.print(",");
hal.console->print(tmp_long);
hal.console->print(",");
tmp_long = DataFlash.ReadLong();
Serial.print(tmp_long);
Serial.print(";");
hal.console->print(tmp_long);
hal.console->print(";");
// Read the checksum...
tmp_byte1 = DataFlash.ReadByte();
tmp_byte2 = DataFlash.ReadByte();
}
Serial.println();
hal.console->println();
}
Serial.println("");
Serial.println("Test complete. Test will repeat in 20 seconds");
Serial.println("");
delay(20000);
hal.console->println("");
hal.console->println("Test complete. Test will repeat in 20 seconds");
hal.console->println("");
hal.scheduler->delay(20000);
}
AP_HAL_MAIN();