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
|
|
|
/*
|
2014-12-02 17:39:36 -04:00
|
|
|
* Example of DataFlash library.
|
|
|
|
* originally based on code by Jordi MuÒoz and Jose Julio
|
2012-08-17 03:21:25 -03:00
|
|
|
*/
|
2011-02-13 20:43:11 -04:00
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <DataFlash/DataFlash.h>
|
2012-10-04 10:46:35 -03:00
|
|
|
|
2015-10-16 17:22:11 -03:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
2012-12-18 21:26:58 -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;
|
|
|
|
};
|
|
|
|
|
2015-10-25 14:03:46 -03:00
|
|
|
static const struct LogStructure log_structure[] = {
|
2013-04-19 21:25:21 -03:00
|
|
|
LOG_COMMON_STRUCTURES,
|
|
|
|
{ LOG_TEST_MSG, sizeof(log_Test),
|
2015-08-01 11:16:45 -03:00
|
|
|
"TEST", "HHHHii", "V1,V2,V3,V4,L1,L2" }
|
2013-04-19 21:25:21 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
#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;
|
|
|
|
|
2015-08-01 11:16:45 -03:00
|
|
|
class DataFlashTest {
|
|
|
|
public:
|
|
|
|
void setup();
|
|
|
|
void loop();
|
|
|
|
|
|
|
|
private:
|
|
|
|
|
2015-10-24 18:45:41 -03:00
|
|
|
DataFlash_Class dataflash{"DF Test 0.1"};
|
2015-08-01 11:16:45 -03:00
|
|
|
void print_mode(AP_HAL::BetterStream *port, uint8_t mode);
|
|
|
|
};
|
|
|
|
|
|
|
|
static DataFlashTest dataflashtest;
|
|
|
|
|
|
|
|
void DataFlashTest::setup(void)
|
2011-02-13 20:43:11 -04:00
|
|
|
{
|
2015-08-01 11:16:45 -03:00
|
|
|
dataflash.Init(log_structure, ARRAY_SIZE(log_structure));
|
2012-08-17 03:21:25 -03:00
|
|
|
|
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);
|
2015-08-01 11:16:45 -03:00
|
|
|
dataflash.ShowDeviceInfo(hal.console);
|
2013-01-12 02:21:21 -04:00
|
|
|
|
2015-08-08 03:13:38 -03:00
|
|
|
if (dataflash.NeedPrep()) {
|
|
|
|
hal.console->println("Preparing dataflash...");
|
|
|
|
dataflash.Prep();
|
2013-01-12 02:21:21 -04:00
|
|
|
}
|
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...
|
2015-12-04 16:02:27 -04:00
|
|
|
dataflash.StartNewLog();
|
|
|
|
log_num = dataflash.find_last_log();
|
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++) {
|
2015-11-19 23:15:24 -04:00
|
|
|
uint32_t start = AP_HAL::micros();
|
2013-01-12 02:21:21 -04:00
|
|
|
// 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),
|
2015-08-01 11:16:45 -03:00
|
|
|
v1 : (uint16_t)(2000 + i),
|
|
|
|
v2 : (uint16_t)(2001 + i),
|
|
|
|
v3 : (uint16_t)(2002 + i),
|
|
|
|
v4 : (uint16_t)(2003 + i),
|
2015-08-03 02:58:57 -03:00
|
|
|
l1 : (int32_t)(i * 5000),
|
|
|
|
l2 : (int32_t)(i * 16268)
|
2013-01-12 02:21:21 -04:00
|
|
|
};
|
2015-08-01 11:16:45 -03:00
|
|
|
dataflash.WriteBlock(&pkt, sizeof(pkt));
|
2015-11-19 23:15:24 -04:00
|
|
|
total_micros += AP_HAL::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",
|
2015-08-03 02:58:57 -03:00
|
|
|
(double)total_micros/((double)i*sizeof(struct log_Test)));
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
|
|
dataflash.flush();
|
|
|
|
#endif
|
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
|
|
|
}
|
|
|
|
|
2015-08-01 11:16:45 -03:00
|
|
|
void DataFlashTest::loop(void)
|
2013-03-14 17:30:40 -03:00
|
|
|
{
|
|
|
|
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
|
|
|
|
2015-08-01 11:16:45 -03:00
|
|
|
dataflash.get_log_boundaries(log_num, start, end);
|
|
|
|
dataflash.LogReadProcess(log_num, start, end,
|
|
|
|
FUNCTOR_BIND_MEMBER(&DataFlashTest::print_mode, void, AP_HAL::BetterStream *, uint8_t),//print_mode,
|
2013-04-20 02:17:49 -03:00
|
|
|
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
|
|
|
|
2015-08-01 11:16:45 -03:00
|
|
|
void DataFlashTest::print_mode(AP_HAL::BetterStream *port, uint8_t mode)
|
|
|
|
{
|
2015-10-25 17:10:41 -03:00
|
|
|
port->printf("Mode(%u)", (unsigned)mode);
|
2015-08-01 11:16:45 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
compatibility with old pde style build
|
|
|
|
*/
|
|
|
|
void setup(void);
|
|
|
|
void loop(void);
|
|
|
|
|
|
|
|
void setup()
|
|
|
|
{
|
|
|
|
dataflashtest.setup();
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
void loop()
|
|
|
|
{
|
|
|
|
dataflashtest.loop();
|
|
|
|
}
|
|
|
|
|
2012-12-12 18:21:04 -04:00
|
|
|
AP_HAL_MAIN();
|