|
|
@ -28,7 +28,13 @@ |
|
|
|
#define AP_MISSION_EEPROM_VERSION 0x65AE // version number stored in first four bytes of eeprom. increment this by one when eeprom format is changed
|
|
|
|
#define AP_MISSION_EEPROM_VERSION 0x65AE // version number stored in first four bytes of eeprom. increment this by one when eeprom format is changed
|
|
|
|
#define AP_MISSION_EEPROM_COMMAND_SIZE 15 // size in bytes of all mission commands
|
|
|
|
#define AP_MISSION_EEPROM_COMMAND_SIZE 15 // size in bytes of all mission commands
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
#ifndef AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS |
|
|
|
|
|
|
|
#if HAL_MEM_CLASS >= HAL_MEM_CLASS_500 |
|
|
|
|
|
|
|
#define AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS 100 // allow up to 100 do-jump commands
|
|
|
|
|
|
|
|
#else |
|
|
|
#define AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS 15 // allow up to 15 do-jump commands
|
|
|
|
#define AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS 15 // allow up to 15 do-jump commands
|
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
#define AP_MISSION_JUMP_REPEAT_FOREVER -1 // when do-jump command's repeat count is -1 this means endless repeat
|
|
|
|
#define AP_MISSION_JUMP_REPEAT_FOREVER -1 // when do-jump command's repeat count is -1 this means endless repeat
|
|
|
|
|
|
|
|
|
|
|
|