APM:Libraries
Storage.cpp
Go to the documentation of this file.
1 /*
2  simple test of Storage API
3  */
4 
5 #include <AP_HAL/AP_HAL.h>
6 
7 void setup();
8 void loop();
9 
11 
12 void setup(void)
13 {
14  /*
15  init Storage API
16  */
17  AP_HAL::Storage *st = hal.storage;
18 
19  hal.console->printf("Starting AP_HAL::Storage test\r\n");
20  st->init();
21 
22  /*
23  Calculate XOR of the full conent of memory
24  Do it by block of 8 bytes
25  */
26  unsigned char buff[8], XOR_res = 0;
27 
28  for (uint32_t i = 0; i < HAL_STORAGE_SIZE; i += 8) {
29  st->read_block((void *) buff, i, 8);
30  for(uint32_t j = 0; j < 8; j++) {
31  XOR_res ^= buff[j];
32  }
33  }
34 
35  /*
36  print XORed result
37  */
38  hal.console->printf("XORed ememory: %u\r\n", (unsigned) XOR_res);
39 }
40 
41 // In main loop do nothing
42 void loop(void)
43 {
44  hal.scheduler->delay(1000);
45 }
46 
47 AP_HAL_MAIN();
#define HAL_STORAGE_SIZE
Definition: empty.h:5
virtual void init()=0
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: Storage.cpp:10
AP_HAL::UARTDriver * console
Definition: HAL.h:110
AP_HAL_MAIN()
void loop()
Definition: Storage.cpp:42
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
virtual void read_block(void *dst, uint16_t src, size_t n)=0
AP_HAL::Storage * storage
Definition: HAL.h:109
const HAL & get_HAL()
void setup()
Definition: Storage.cpp:12
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114