From 3357df95298ad70ae9354251ddfbb7bf2dcbf60b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 14 Aug 2014 10:48:31 +1000 Subject: [PATCH] AP_Mission: fixed example sketch --- .../AP_Mission_test/AP_Mission_test.pde | 34 +++++-------------- .../examples/AP_Mission_test/Makefile | 1 + 2 files changed, 10 insertions(+), 25 deletions(-) create mode 100644 libraries/AP_Mission/examples/AP_Mission_test/Makefile diff --git a/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.pde b/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.pde index 009df2cd15..378d3d2882 100644 --- a/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.pde +++ b/libraries/AP_Mission/examples/AP_Mission_test/AP_Mission_test.pde @@ -10,11 +10,17 @@ #include #include #include +#include +#include +#include +#include +#include #include #include #include #include #include +#include #include #include #include // ArduPilot GPS library @@ -31,30 +37,10 @@ #include // ArduPilot general purpose FIFO buffer #include -// storage locations equivalent to ArduCopter -// fence points are stored at the end of the EEPROM -#define MAX_FENCEPOINTS 6 -#define FENCE_WP_SIZE sizeof(Vector2l) -#define FENCE_START_BYTE (HAL_STORAGE_SIZE_AVAILABLE-(MAX_FENCEPOINTS*FENCE_WP_SIZE)) - -// parameters get the first 1536 bytes of EEPROM, mission commands are stored between these params and the fence points -#define MISSION_START_BYTE 0x500 -#define MISSION_END_BYTE (FENCE_START_BYTE-1) - const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; -// INS and Baro declaration -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 - -AP_InertialSensor_MPU6000 ins; -AP_Baro_MS5611 baro(&AP_Baro_MS5611::spi); - -#else - -AP_ADC_ADS7844 adc; -AP_InertialSensor_Oilpan ins(&adc); -AP_Baro_BMP085 baro; -#endif +AP_InertialSensor_HIL ins; +AP_Baro_HIL baro; // GPS declaration static AP_GPS gps; @@ -117,7 +103,7 @@ void mission_complete(void) } // declaration -AP_Mission mission(ahrs, &start_cmd, &verify_cmd, &mission_complete, MISSION_START_BYTE, MISSION_END_BYTE); +AP_Mission mission(ahrs, &start_cmd, &verify_cmd, &mission_complete); // setup void setup(void) @@ -127,8 +113,6 @@ void setup(void) // display basic info about command sizes hal.console->printf_P(PSTR("Max Num Commands: %d\n"),(int)mission.num_commands_max()); hal.console->printf_P(PSTR("Command size: %d bytes\n"),(int)AP_MISSION_EEPROM_COMMAND_SIZE); - hal.console->printf_P(PSTR("Command start in Eeprom: 0x%x\n"),(int)MISSION_START_BYTE); - hal.console->printf_P(PSTR("Command end in Eeprom: 0x%x\n"),(int)MISSION_END_BYTE); } // loop diff --git a/libraries/AP_Mission/examples/AP_Mission_test/Makefile b/libraries/AP_Mission/examples/AP_Mission_test/Makefile new file mode 100644 index 0000000000..f5daf25151 --- /dev/null +++ b/libraries/AP_Mission/examples/AP_Mission_test/Makefile @@ -0,0 +1 @@ +include ../../../../mk/apm.mk