mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Copter: pass eeprom start to Mission constructor
This commit is contained in:
parent
8e117d29eb
commit
b587d0d597
@ -353,7 +353,7 @@ AP_AHRS_DCM ahrs(ins, barometer, g_gps);
|
||||
static bool start_command(const AP_Mission::Mission_Command& cmd);
|
||||
static bool verify_command(const AP_Mission::Mission_Command& cmd);
|
||||
static void exit_mission();
|
||||
AP_Mission mission(ahrs, &start_command, &verify_command, &exit_mission);
|
||||
AP_Mission mission(ahrs, &start_command, &verify_command, &exit_mission, MISSION_START_BYTE, MISSION_END_BYTE);
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Optical flow sensor
|
||||
@ -759,7 +759,7 @@ static void pre_arm_checks(bool display_failure);
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
// setup the var_info table
|
||||
AP_Param param_loader(var_info, WP_START_BYTE);
|
||||
AP_Param param_loader(var_info, MISSION_START_BYTE);
|
||||
|
||||
#if MAIN_LOOP_RATE == 400
|
||||
/*
|
||||
|
@ -296,24 +296,14 @@ enum FlipState {
|
||||
// Centi-degrees to radians
|
||||
#define DEGX100 5729.57795f
|
||||
|
||||
|
||||
// EEPROM addresses
|
||||
#define EEPROM_MAX_ADDR 4096
|
||||
// parameters get the first 1536 bytes of EEPROM, remainder is for waypoints
|
||||
#define WP_START_BYTE 0x600 // where in memory home WP is stored + all other
|
||||
// WP
|
||||
#define WP_SIZE 15
|
||||
|
||||
// fence points are stored at the end of the EEPROM
|
||||
#define MAX_FENCEPOINTS 6
|
||||
#define FENCE_WP_SIZE sizeof(Vector2l)
|
||||
#define FENCE_START_BYTE (EEPROM_MAX_ADDR-(MAX_FENCEPOINTS*FENCE_WP_SIZE))
|
||||
#define FENCE_START_BYTE (HAL_STORAGE_SIZE_AVAILABLE-(MAX_FENCEPOINTS*FENCE_WP_SIZE))
|
||||
|
||||
#define MAX_WAYPOINTS ((FENCE_START_BYTE - WP_START_BYTE) / WP_SIZE) - 1 // -
|
||||
// 1
|
||||
// to
|
||||
// be
|
||||
// safe
|
||||
// parameters get the first 1536 bytes of EEPROM, mission commands are stored between these params and the fence points
|
||||
#define MISSION_START_BYTE 0x600
|
||||
#define MISSION_END_BYTE (FENCE_START_BYTE-1)
|
||||
|
||||
// mark a function as not to be inlined
|
||||
#define NOINLINE __attribute__((noinline))
|
||||
|
Loading…
Reference in New Issue
Block a user