Mission: allow 15 do-jump commands on Pixhawk

This commit is contained in:
Randy Mackay 2014-12-18 17:01:56 +09:00
parent 05fedbf98f
commit a44b4b5e87

View File

@ -27,7 +27,12 @@
#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_MAX_NUM_DO_JUMP_COMMANDS 3 // only allow up to 3 do-jump commands (due to RAM limitations on the APM2)
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75
# define AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS 3 // allow up to 3 do-jump commands (due to RAM limitations) on the APM2
#else
# define AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS 15 // allow up to 15 do-jump commands all high speed CPUs
#endif
#define AP_MISSION_JUMP_REPEAT_FOREVER -1 // when do-jump command's repeat count is -1 this means endless repeat
#define AP_MISSION_CMD_ID_NONE 0 // mavlink cmd id of zero means invalid or missing command