2013-01-12 02:21:21 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
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
|
2013-03-10 23:02:08 -03:00
|
|
|
#include <AP_HAL.h>
|
|
|
|
#include <AP_HAL_AVR.h>
|
|
|
|
#include <AP_HAL_AVR_SITL.h>
|
|
|
|
#include <AP_HAL_Empty.h>
|
|
|
|
#include <AP_HAL_PX4.h>
|
|
|
|
|
2012-10-04 10:46:35 -03:00
|
|
|
#include <AP_Common.h>
|
2012-12-12 18:21:04 -04:00
|
|
|
#include <AP_Param.h>
|
|
|
|
#include <AP_Progmem.h>
|
2013-04-19 21:25:21 -03:00
|
|
|
#include <AP_Math.h>
|
|
|
|
#include <AP_Compass.h>
|
|
|
|
#include <Filter.h>
|
|
|
|
#include <AP_Declination.h>
|
|
|
|
#include <AP_Airspeed.h>
|
|
|
|
#include <AP_Baro.h>
|
|
|
|
#include <AP_AHRS.h>
|
|
|
|
#include <AP_ADC.h>
|
2013-07-15 01:10:58 -03:00
|
|
|
#include <AP_ADC_AnalogSource.h>
|
2013-04-19 21:25:21 -03:00
|
|
|
#include <AP_InertialSensor.h>
|
|
|
|
#include <AP_GPS.h>
|
2011-02-13 20:43:11 -04:00
|
|
|
#include <DataFlash.h>
|
2013-05-08 03:45:40 -03:00
|
|
|
#include <GCS_MAVLink.h>
|
2013-08-29 02:03:33 -03:00
|
|
|
#include <AP_Notify.h>
|
2013-09-12 22:44:42 -03:00
|
|
|
#include <AP_Vehicle.h>
|
2011-02-13 20:43:11 -04:00
|
|
|
|
2012-12-12 18:21:04 -04:00
|
|
|
|
2012-10-04 10:46:35 -03:00
|
|
|
|
2012-12-18 21:26:58 -04:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
|
|
|
|
2012-12-12 18:21:04 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
|
|
|
DataFlash_APM2 DataFlash;
|
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
|
|
|
DataFlash_APM1 DataFlash;
|
2013-03-14 17:30:40 -03:00
|
|
|
#else
|
|
|
|
DataFlash_Empty DataFlash;
|
2012-12-12 18:21:04 -04:00
|
|
|
#endif
|
2012-01-09 00:26:56 -04:00
|
|
|
|
2013-04-19 21:25:21 -03:00
|
|
|
#define LOG_TEST_MSG 1
|
2013-03-14 17:30:40 -03:00
|
|
|
|
2013-04-19 21:25:21 -03:00
|
|
|
struct PACKED log_Test {
|
2013-01-12 07:16:32 -04:00
|
|
|
LOG_PACKET_HEADER;
|
2013-01-12 02:21:21 -04:00
|
|
|
uint16_t v1, v2, v3, v4;
|
|
|
|
int32_t l1, l2;
|
|
|
|
};
|
|
|
|
|
2013-04-19 21:25:21 -03:00
|
|
|
static const struct LogStructure log_structure[] PROGMEM = {
|
|
|
|
LOG_COMMON_STRUCTURES,
|
|
|
|
{ LOG_TEST_MSG, sizeof(log_Test),
|
|
|
|
"TEST", "HHHHii", "V1,V2,V3,V4,L1,L2" }
|
|
|
|
};
|
|
|
|
|
|
|
|
#define NUM_PACKETS 500
|
2012-01-09 00:26:56 -04:00
|
|
|
|
2013-03-14 17:30:40 -03:00
|
|
|
static uint16_t log_num;
|
|
|
|
|
2011-02-13 20:43:11 -04:00
|
|
|
void setup()
|
|
|
|
{
|
2012-08-17 03:21:25 -03:00
|
|
|
DataFlash.Init(); // DataFlash initialization
|
|
|
|
|
2012-12-12 18:21:04 -04:00
|
|
|
hal.console->println("Dataflash Log Test 1.0");
|
2012-08-17 03:21:25 -03:00
|
|
|
|
|
|
|
// Test
|
2012-12-12 18:21:04 -04:00
|
|
|
hal.scheduler->delay(20);
|
2012-08-17 03:21:25 -03:00
|
|
|
DataFlash.ReadManufacturerID();
|
2012-12-12 18:21:04 -04:00
|
|
|
hal.scheduler->delay(10);
|
2013-03-10 23:02:08 -03:00
|
|
|
DataFlash.ShowDeviceInfo(hal.console);
|
2013-01-12 02:21:21 -04:00
|
|
|
|
|
|
|
if (DataFlash.NeedErase()) {
|
|
|
|
hal.console->println("Erasing...");
|
|
|
|
DataFlash.EraseAll();
|
|
|
|
}
|
2012-08-17 03:21:25 -03:00
|
|
|
|
|
|
|
// We start to write some info (sequentialy) starting from page 1
|
|
|
|
// This is similar to what we will do...
|
2013-04-19 21:25:21 -03:00
|
|
|
log_num = DataFlash.StartNewLog(sizeof(log_structure)/sizeof(log_structure[0]), log_structure);
|
2013-03-14 17:30:40 -03:00
|
|
|
hal.console->printf("Using log number %u\n", log_num);
|
2012-12-12 18:21:04 -04:00
|
|
|
hal.console->println("After testing perform erase before using DataFlash for logging!");
|
|
|
|
hal.console->println("");
|
|
|
|
hal.console->println("Writing to flash... wait...");
|
2013-01-12 02:21:21 -04:00
|
|
|
|
|
|
|
uint32_t total_micros = 0;
|
|
|
|
uint16_t i;
|
|
|
|
|
|
|
|
for (i = 0; i < NUM_PACKETS; i++) {
|
|
|
|
uint32_t start = hal.scheduler->micros();
|
|
|
|
// note that we use g++ style initialisers to make larger
|
|
|
|
// structures easier to follow
|
2013-04-19 21:25:21 -03:00
|
|
|
struct log_Test pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_TEST_MSG),
|
2013-01-12 02:21:21 -04:00
|
|
|
v1 : 2000 + i,
|
|
|
|
v2 : 2001 + i,
|
|
|
|
v3 : 2002 + i,
|
|
|
|
v4 : 2003 + i,
|
|
|
|
l1 : (long)i * 5000,
|
2013-01-12 07:16:32 -04:00
|
|
|
l2 : (long)i * 16268
|
2013-01-12 02:21:21 -04:00
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
total_micros += hal.scheduler->micros() - start;
|
2013-01-12 07:16:32 -04:00
|
|
|
hal.scheduler->delay(20);
|
2012-08-17 03:21:25 -03:00
|
|
|
}
|
2013-01-12 02:21:21 -04:00
|
|
|
|
|
|
|
hal.console->printf("Average write time %.1f usec/byte\n",
|
2013-04-19 21:25:21 -03:00
|
|
|
(double)total_micros/((float)i*sizeof(struct log_Test)));
|
2013-01-12 02:21:21 -04:00
|
|
|
|
2012-12-12 18:21:04 -04:00
|
|
|
hal.scheduler->delay(100);
|
2011-02-13 20:43:11 -04:00
|
|
|
}
|
|
|
|
|
2013-04-20 02:17:49 -03:00
|
|
|
static void
|
|
|
|
print_mode(AP_HAL::BetterStream *port, uint8_t mode)
|
|
|
|
{
|
|
|
|
port->printf_P(PSTR("Mode(%u)"), (unsigned)mode);
|
|
|
|
}
|
|
|
|
|
2013-03-14 17:30:40 -03:00
|
|
|
void loop()
|
|
|
|
{
|
|
|
|
uint16_t start, end;
|
2012-08-17 03:21:25 -03:00
|
|
|
|
2013-03-14 17:30:40 -03:00
|
|
|
hal.console->printf("Start read of log %u\n", log_num);
|
2012-08-17 03:21:25 -03:00
|
|
|
|
2013-03-14 17:30:40 -03:00
|
|
|
DataFlash.get_log_boundaries(log_num, start, end);
|
2013-04-19 21:25:21 -03:00
|
|
|
DataFlash.LogReadProcess(log_num, start, end,
|
|
|
|
sizeof(log_structure)/sizeof(log_structure[0]),
|
2013-04-20 02:17:49 -03:00
|
|
|
log_structure,
|
|
|
|
print_mode,
|
|
|
|
hal.console);
|
2013-01-12 02:21:21 -04:00
|
|
|
hal.console->printf("\nTest complete. Test will repeat in 20 seconds\n");
|
2012-12-12 18:21:04 -04:00
|
|
|
hal.scheduler->delay(20000);
|
2012-09-05 17:23:20 -03:00
|
|
|
}
|
2012-12-12 18:21:04 -04:00
|
|
|
|
|
|
|
AP_HAL_MAIN();
|