mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Change to increase Parameter space as we have run out.
This will decrease the max number of waypoints from 186 to 169.
This commit is contained in:
parent
abb426aec3
commit
3df1aac936
@ -358,8 +358,8 @@ enum gcs_severity {
|
||||
|
||||
// EEPROM addresses
|
||||
#define EEPROM_MAX_ADDR 4096
|
||||
// parameters get the first 1280 bytes of EEPROM, remainder is for waypoints
|
||||
#define WP_START_BYTE 0x500 // where in memory home WP is stored + all other WP
|
||||
// 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
|
||||
|
||||
#define ONBOARD_PARAM_NAME_LENGTH 15
|
||||
|
Loading…
Reference in New Issue
Block a user