3 changed files with 116 additions and 0 deletions
@ -0,0 +1 @@ |
|||||||
|
include ../../../../mk/apm.mk |
@ -0,0 +1,82 @@ |
|||||||
|
/*
|
||||||
|
simple test of Storage API |
||||||
|
*/ |
||||||
|
#include <AP_HAL.h> |
||||||
|
#include <AP_HAL_AVR.h> |
||||||
|
#include <AP_HAL_SITL.h> |
||||||
|
#include <AP_HAL_PX4.h> |
||||||
|
#include <AP_HAL_Linux.h> |
||||||
|
#include <AP_HAL_Empty.h> |
||||||
|
#include <AP_Common.h> |
||||||
|
#include <AP_Baro.h> |
||||||
|
#include <AP_ADC.h> |
||||||
|
#include <AP_GPS.h> |
||||||
|
#include <AP_InertialSensor.h> |
||||||
|
#include <AP_Notify.h> |
||||||
|
#include <DataFlash.h> |
||||||
|
#include <GCS_MAVLink.h> |
||||||
|
#include <AP_Mission.h> |
||||||
|
#include <StorageManager.h> |
||||||
|
#include <AP_Terrain.h> |
||||||
|
#include <AP_Compass.h> |
||||||
|
#include <AP_Declination.h> |
||||||
|
#include <SITL.h> |
||||||
|
#include <Filter.h> |
||||||
|
#include <AP_Param.h> |
||||||
|
#include <AP_Progmem.h> |
||||||
|
#include <AP_Math.h> |
||||||
|
#include <AP_AHRS.h> |
||||||
|
#include <AP_Airspeed.h> |
||||||
|
#include <AP_Vehicle.h> |
||||||
|
#include <AP_ADC_AnalogSource.h> |
||||||
|
#include <AP_NavEKF.h> |
||||||
|
#include <AP_Rally.h> |
||||||
|
#include <AP_Scheduler.h> |
||||||
|
#include <UARTDriver.h> |
||||||
|
#include <AP_BattMonitor.h> |
||||||
|
#include <AP_RangeFinder.h> |
||||||
|
#include <AP_HAL_Boards.h> |
||||||
|
|
||||||
|
#if HAL_OS_POSIX_IO |
||||||
|
#include <stdio.h> |
||||||
|
#endif |
||||||
|
|
||||||
|
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; |
||||||
|
|
||||||
|
AP_HAL::Storage *st; |
||||||
|
|
||||||
|
void setup(void)
|
||||||
|
{ |
||||||
|
/*
|
||||||
|
init Storage API |
||||||
|
*/ |
||||||
|
hal.console->printf_P(PSTR("Starting AP_HAL::Storage test\r\n")); |
||||||
|
st->init(); |
||||||
|
|
||||||
|
/*
|
||||||
|
Calculate XOR of the full conent of memory |
||||||
|
Do it by block of 8 bytes |
||||||
|
*/ |
||||||
|
unsigned int i, j; |
||||||
|
unsigned char buff[8], XOR_res = 0; |
||||||
|
|
||||||
|
for(i = 0; i < HAL_STORAGE_SIZE; i += 8) |
||||||
|
{ |
||||||
|
st->read_block((void *) buff, i, 8); |
||||||
|
for(j = 0; j < 8; j++) |
||||||
|
XOR_res ^= buff[j]; |
||||||
|
} |
||||||
|
|
||||||
|
/*
|
||||||
|
print XORed result |
||||||
|
*/ |
||||||
|
hal.console->printf_P(PSTR("XORed ememory: %u\r\n"), (unsigned) XOR_res); |
||||||
|
} |
||||||
|
|
||||||
|
// In main loop do nothing
|
||||||
|
void loop(void)
|
||||||
|
{
|
||||||
|
hal.scheduler->delay(1000); |
||||||
|
} |
||||||
|
|
||||||
|
AP_HAL_MAIN(); |
@ -0,0 +1,33 @@ |
|||||||
|
LIBRARIES += AP_ADC |
||||||
|
LIBRARIES += AP_ADC_AnalogSource |
||||||
|
LIBRARIES += AP_AHRS |
||||||
|
LIBRARIES += AP_Airspeed |
||||||
|
LIBRARIES += AP_Baro |
||||||
|
LIBRARIES += AP_BattMonitor |
||||||
|
LIBRARIES += AP_Common |
||||||
|
LIBRARIES += AP_Compass |
||||||
|
LIBRARIES += AP_Declination |
||||||
|
LIBRARIES += AP_GPS |
||||||
|
LIBRARIES += AP_HAL |
||||||
|
LIBRARIES += AP_HAL_AVR |
||||||
|
LIBRARIES += AP_HAL_Empty |
||||||
|
LIBRARIES += AP_HAL_Linux |
||||||
|
LIBRARIES += AP_HAL_PX4 |
||||||
|
LIBRARIES += AP_HAL_SITL |
||||||
|
LIBRARIES += AP_InertialSensor |
||||||
|
LIBRARIES += AP_Math |
||||||
|
LIBRARIES += AP_Mission |
||||||
|
LIBRARIES += AP_NavEKF |
||||||
|
LIBRARIES += AP_Notify |
||||||
|
LIBRARIES += AP_Param |
||||||
|
LIBRARIES += AP_Progmem |
||||||
|
LIBRARIES += AP_Rally |
||||||
|
LIBRARIES += AP_RangeFinder |
||||||
|
LIBRARIES += AP_Scheduler |
||||||
|
LIBRARIES += AP_Terrain |
||||||
|
LIBRARIES += AP_Vehicle |
||||||
|
LIBRARIES += DataFlash |
||||||
|
LIBRARIES += Filter |
||||||
|
LIBRARIES += GCS_MAVLink |
||||||
|
LIBRARIES += SITL |
||||||
|
LIBRARIES += StorageManager |
Loading…
Reference in new issue