From 0641159660aa7e22037e4a3e2f0b0277858bad8f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 17 Dec 2013 11:51:12 +1100 Subject: [PATCH] DataFlash: fixed example build --- .../DataFlash/examples/DataFlash_test/DataFlash_test.pde | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.pde b/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.pde index 9699da4cf6..992e11dd3c 100644 --- a/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.pde +++ b/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.pde @@ -62,7 +62,7 @@ static uint16_t log_num; void setup() { - DataFlash.Init(); // DataFlash initialization + DataFlash.Init(log_structure, sizeof(log_structure)/sizeof(log_structure[0])); hal.console->println("Dataflash Log Test 1.0"); @@ -79,7 +79,7 @@ void setup() // We start to write some info (sequentialy) starting from page 1 // This is similar to what we will do... - log_num = DataFlash.StartNewLog(sizeof(log_structure)/sizeof(log_structure[0]), log_structure); + log_num = DataFlash.StartNewLog(); hal.console->printf("Using log number %u\n", log_num); hal.console->println("After testing perform erase before using DataFlash for logging!"); hal.console->println(""); @@ -126,8 +126,6 @@ void loop() DataFlash.get_log_boundaries(log_num, start, end); DataFlash.LogReadProcess(log_num, start, end, - sizeof(log_structure)/sizeof(log_structure[0]), - log_structure, print_mode, hal.console); hal.console->printf("\nTest complete. Test will repeat in 20 seconds\n");