2022-02-21 00:40:40 -04:00
# include <AP_HAL/AP_HAL_Boards.h>
2019-05-26 22:46:41 -03:00
# include "AP_Periph.h"
extern const AP_HAL : : HAL & hal ;
2020-12-26 15:18:08 -04:00
# ifndef HAL_PERIPH_LED_BRIGHT_DEFAULT
# define HAL_PERIPH_LED_BRIGHT_DEFAULT 100
2019-10-18 21:28:09 -03:00
# endif
2020-12-26 15:18:08 -04:00
# ifndef HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT
# define HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT 115200
2020-12-22 19:29:59 -04:00
# endif
2022-01-27 23:55:01 -04:00
# ifndef AP_PERIPH_RANGEFINDER_PORT_DEFAULT
# define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 3
2020-12-22 19:29:59 -04:00
# endif
# ifndef HAL_PERIPH_GPS_PORT_DEFAULT
# define HAL_PERIPH_GPS_PORT_DEFAULT 3
# endif
2020-01-24 19:59:01 -04:00
# ifndef HAL_PERIPH_ADSB_BAUD_DEFAULT
# define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600
# endif
2020-12-17 22:12:25 -04:00
# ifndef HAL_PERIPH_ADSB_PORT_DEFAULT
# define HAL_PERIPH_ADSB_PORT_DEFAULT 1
# endif
2020-01-24 19:59:01 -04:00
2020-12-26 19:35:15 -04:00
# ifndef AP_PERIPH_MSP_PORT_DEFAULT
# define AP_PERIPH_MSP_PORT_DEFAULT 1
# endif
2021-12-07 04:09:41 -04:00
# ifndef AP_PERIPH_ESC_TELEM_PORT_DEFAULT
# define AP_PERIPH_ESC_TELEM_PORT_DEFAULT -1
# endif
2022-01-27 23:53:35 -04:00
# ifndef AP_PERIPH_BARO_ENABLE_DEFAULT
# define AP_PERIPH_BARO_ENABLE_DEFAULT 1
# endif
2021-06-20 03:02:12 -03:00
# ifndef HAL_DEFAULT_MAV_SYSTEM_ID
# define MAV_SYSTEM_ID 3
# else
# define MAV_SYSTEM_ID HAL_DEFAULT_MAV_SYSTEM_ID
# endif
2019-05-26 22:46:41 -03:00
/*
* AP_Periph parameter definitions
*
*/
# define GSCALAR(v, name, def) { periph.g.v.vtype, name, Parameters::k_param_ ## v, &periph.g.v, {def_value : def} }
2021-04-30 22:36:42 -03:00
# define GARRAY(v, index, name, def) { periph.g.v[index].vtype, name, Parameters::k_param_ ## v ## index, &periph.g.v[index], {def_value : def} }
2019-05-26 22:46:41 -03:00
# define ASCALAR(v, name, def) { periph.aparm.v.vtype, name, Parameters::k_param_ ## v, (const void *)&periph.aparm.v, {def_value : def} }
# define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &periph.g.v, {group_info : class::var_info} }
# define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&periph.v, {group_info : class::var_info} }
# define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, (const void *)&periph.v, {group_info : class::var_info} }
const AP_Param : : Info AP_Periph_FW : : var_info [ ] = {
// @Param: FORMAT_VERSION
// @DisplayName: Eeprom format version number
// @Description: This value is incremented when changes are made to the eeprom format
// @User: Advanced
GSCALAR ( format_version , " FORMAT_VERSION " , 0 ) ,
2021-04-18 19:29:15 -03:00
// @Param: CAN_NODE
// @DisplayName: UAVCAN node that is used for this network
// @Description: UAVCAN node should be set implicitly or 0 for dynamic node allocation
// @Range: 0 250
// @User: Advanced
// @RebootRequired: True
2019-05-26 22:46:41 -03:00
GSCALAR ( can_node , " CAN_NODE " , HAL_CAN_DEFAULT_NODE_ID ) ,
2021-04-18 19:29:15 -03:00
// @Param: CAN_BAUDRATE
// @DisplayName: Bitrate of CAN interface
// @Description: Bit rate can be set up to from 10000 to 1000000
// @Range: 10000 1000000
// @User: Advanced
// @RebootRequired: True
2021-04-30 22:36:42 -03:00
GARRAY ( can_baudrate , 0 , " CAN_BAUDRATE " , 1000000 ) ,
# if HAL_NUM_CAN_IFACES >= 2
// @Param: CAN_PROTOCOL
// @DisplayName: Enable use of specific protocol to be used on this port
// @Description: Enabling this option starts selected protocol that will use this virtual driver. At least one CAN port must be UAVCAN or else CAN1 gets set to UAVCAN
2021-12-17 02:05:07 -04:00
// @Values: 0:Disabled,1:UAVCAN,3:ToshibaCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN
2021-04-30 22:36:42 -03:00
// @User: Advanced
// @RebootRequired: True
GARRAY ( can_protocol , 0 , " CAN_PROTOCOL " , AP_CANManager : : Driver_Type_UAVCAN ) ,
// @Param: CAN2_BAUDRATE
// @DisplayName: Bitrate of CAN2 interface
// @Description: Bit rate can be set up to from 10000 to 1000000
// @Range: 10000 1000000
// @User: Advanced
// @RebootRequired: True
GARRAY ( can_baudrate , 1 , " CAN2_BAUDRATE " , 1000000 ) ,
// @Param: CAN2_PROTOCOL
// @DisplayName: Enable use of specific protocol to be used on this port
// @Description: Enabling this option starts selected protocol that will use this virtual driver. At least one CAN port must be UAVCAN or else CAN1 gets set to UAVCAN
2021-12-17 02:05:07 -04:00
// @Values: 0:Disabled,1:UAVCAN,3:ToshibaCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN
2021-04-30 22:36:42 -03:00
// @User: Advanced
// @RebootRequired: True
GARRAY ( can_protocol , 1 , " CAN2_PROTOCOL " , AP_CANManager : : Driver_Type_UAVCAN ) ,
# endif
# if HAL_NUM_CAN_IFACES >= 3
// @Param: CAN3_BAUDRATE
// @DisplayName: Bitrate of CAN3 interface
// @Description: Bit rate can be set up to from 10000 to 1000000
// @Range: 10000 1000000
// @User: Advanced
// @RebootRequired: True
GARRAY ( can_baudrate , 2 , " CAN3_BAUDRATE " , 1000000 ) ,
// @Param: CAN3_PROTOCOL
// @DisplayName: Enable use of specific protocol to be used on this port
// @Description: Enabling this option starts selected protocol that will use this virtual driver. At least one CAN port must be UAVCAN or else CAN1 gets set to UAVCAN
2021-12-17 02:05:07 -04:00
// @Values: 0:Disabled,1:UAVCAN,3:ToshibaCAN,4:PiccoloCAN,5:CANTester,6:EFI_NWPMU,7:USD1,8:KDECAN
2021-04-30 22:36:42 -03:00
// @User: Advanced
// @RebootRequired: True
GARRAY ( can_protocol , 2 , " CAN3_PROTOCOL " , AP_CANManager : : Driver_Type_UAVCAN ) ,
# endif
2019-10-23 04:57:27 -03:00
2022-02-23 04:21:20 -04:00
# if HAL_CANFD_SUPPORTED
// @Param: CAN_FDMODE
// @DisplayName: Enable CANFD mode
// @Description: Enabling this option sets the CAN bus to be in CANFD mode with BRS.
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
// @RebootRequired: True
GSCALAR ( can_fdmode , " CAN_FDMODE " , 0 ) ,
// @Param: CAN_FDBAUDRATE
// @DisplayName: Set up bitrate for data section on CAN1
// @Description: This sets the bitrate for the data section of CAN1.
// @Values: 1:1M, 2:2M, 4:4M, 5:5M, 8:8M
// @User: Advanced
// @RebootRequired: True
GARRAY ( can_fdbaudrate , 0 , " CAN_FDBAUDRATE " , HAL_CANFD_SUPPORTED ) ,
# if HAL_NUM_CAN_IFACES >= 2
// @Param: CAN2_FDBAUDRATE
// @DisplayName: Set up bitrate for data section on CAN2
// @Description: This sets the bitrate for the data section of CAN2.
// @Values: 1:1M, 2:2M, 4:4M, 5:5M, 8:8M
// @User: Advanced
// @RebootRequired: True
GARRAY ( can_fdbaudrate , 1 , " CAN2_FDBAUDRATE " , HAL_CANFD_SUPPORTED ) ,
# endif
# endif
2019-10-23 04:57:27 -03:00
# if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
2021-04-18 19:29:15 -03:00
// @Param: FLASH_BOOTLOADER
// @DisplayName: Trigger bootloader update
// @Description: DANGER! When enabled, the App will perform a bootloader update by copying the embedded bootloader over the existing bootloader. This may take a few seconds to perform and should only be done if you know what you're doing.
// @Range: 0 1
// @User: Advanced
2019-10-23 04:57:27 -03:00
GSCALAR ( flash_bootloader , " FLASH_BOOTLOADER " , 0 ) ,
# endif
2020-11-29 19:14:56 -04:00
2021-04-18 19:29:15 -03:00
// @Param: DEBUG
// @DisplayName: Debug
// @Description: Debug
2022-03-08 04:51:27 -04:00
// @Bitmask: 0:Disabled, 1:Show free stack space, 2:Auto Reboot after 15sec
2021-04-18 19:29:15 -03:00
// @User: Advanced
2020-11-29 19:14:56 -04:00
GSCALAR ( debug , " DEBUG " , 0 ) ,
2022-03-08 04:51:27 -04:00
2021-04-18 19:29:15 -03:00
// @Param: BRD_SERIAL_NUM
// @DisplayName: Serial number of device
// @Description: Non-zero positive values will be shown on the CAN App Name string
// @Range: 0 2147483648
// @User: Advanced
2020-12-17 01:46:31 -04:00
GSCALAR ( serial_number , " BRD_SERIAL_NUM " , 0 ) ,
2020-12-29 01:06:44 -04:00
# ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY
2021-04-21 20:55:53 -03:00
// @Param: BUZZER_VOLUME
2021-04-18 19:29:15 -03:00
// @DisplayName: Buzzer volume
// @Description: Control the volume of the buzzer
// @Range: 0 100
// @Units: %
// @Increment: 1
// @User: Advanced
2019-08-31 04:20:53 -03:00
GSCALAR ( buzz_volume , " BUZZER_VOLUME " , 100 ) ,
# endif
2019-05-26 22:46:41 -03:00
# ifdef HAL_PERIPH_ENABLE_GPS
// GPS driver
2020-12-30 11:02:31 -04:00
// @Group: GPS
2021-04-10 21:01:27 -03:00
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
2020-12-30 11:02:31 -04:00
GOBJECT ( gps , " GPS " , AP_GPS ) ,
2020-12-22 19:29:59 -04:00
// @Param: GPS_PORT
// @DisplayName: GPS Serial Port
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to GPS.
// @Range: 0 10
// @Increment: 1
// @User: Advanced
// @RebootRequired: True
GSCALAR ( gps_port , " GPS_PORT " , HAL_PERIPH_GPS_PORT_DEFAULT ) ,
2021-07-16 13:16:24 -03:00
2022-03-08 01:25:53 -04:00
# if GPS_MOVING_BASELINE
2021-07-16 13:16:24 -03:00
// @Param: MB_CAN_PORT
// @DisplayName: Moving Baseline CAN Port option
// @Description: Autoselect dedicated CAN port on which moving baseline data will be transmitted.
// @Values: 0:Sends moving baseline data on all ports,1:auto select remaining port for transmitting Moving baseline Data
// @User: Advanced
// @RebootRequired: True
GSCALAR ( gps_mb_only_can_port , " GPS_MB_ONLY_PORT " , 0 ) ,
# endif
2019-05-26 22:46:41 -03:00
# endif
2020-11-21 01:29:10 -04:00
# ifdef HAL_PERIPH_ENABLE_BATTERY
// @Group: BATT
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
GOBJECT ( battery , " BATT " , AP_BattMonitor ) ,
# endif
2019-05-26 22:46:41 -03:00
# ifdef HAL_PERIPH_ENABLE_MAG
2021-12-04 00:22:57 -04:00
// @Group: COMPASS_
2021-04-10 21:01:27 -03:00
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
2021-12-04 00:22:57 -04:00
GOBJECT ( compass , " COMPASS_ " , Compass ) ,
2019-05-26 22:46:41 -03:00
# endif
# ifdef HAL_PERIPH_ENABLE_BARO
// Baro driver
2020-12-03 04:13:33 -04:00
// @Group: BARO
2021-04-10 21:01:27 -03:00
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
2020-12-03 04:13:33 -04:00
GOBJECT ( baro , " BARO " , AP_Baro ) ,
2021-04-18 19:29:15 -03:00
// @Param: BARO_ENABLE
// @DisplayName: Barometer Enable
// @Description: Barometer Enable
// @Values: 0:Disabled, 1:Enabled
// @User: Standard
2022-01-27 23:53:35 -04:00
GSCALAR ( baro_enable , " BARO_ENABLE " , AP_PERIPH_BARO_ENABLE_DEFAULT ) ,
2019-05-26 22:46:41 -03:00
# endif
2019-08-31 04:20:53 -03:00
2020-12-29 01:06:44 -04:00
# ifdef AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
2021-04-18 19:29:15 -03:00
// @Param: LED_BRIGHTNESS
// @DisplayName: LED Brightness
// @Description: Select the RGB LED brightness level.
// @Range: 0 100
// @Units: %
// @Increment: 1
// @User: Standard
2020-12-26 15:18:08 -04:00
GSCALAR ( led_brightness , " LED_BRIGHTNESS " , HAL_PERIPH_LED_BRIGHT_DEFAULT ) ,
2019-10-10 00:18:59 -03:00
# endif
2019-10-03 08:02:56 -03:00
# ifdef HAL_PERIPH_ENABLE_AIRSPEED
// Airspeed driver
// @Group: ARSP
2021-04-10 21:01:27 -03:00
// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp
2019-10-03 08:02:56 -03:00
GOBJECT ( airspeed , " ARSP " , AP_Airspeed ) ,
# endif
2019-10-19 01:36:14 -03:00
2019-10-27 21:31:29 -03:00
# ifdef HAL_PERIPH_ENABLE_RANGEFINDER
2021-04-18 19:29:15 -03:00
// @Param: RNGFND_BAUDRATE
// @DisplayName: Rangefinder serial baudrate
// @Description: Rangefinder serial baudrate.
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000
// @Increment: 1
// @User: Standard
// @RebootRequired: True
2020-12-26 15:18:08 -04:00
GSCALAR ( rangefinder_baud , " RNGFND_BAUDRATE " , HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT ) ,
2021-04-18 19:29:15 -03:00
// @Param: RNGFND_PORT
// @DisplayName: Rangefinder Serial Port
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Rangefinder.
// @Range: 0 10
// @Increment: 1
// @User: Advanced
// @RebootRequired: True
2022-01-27 23:55:01 -04:00
GSCALAR ( rangefinder_port , " RNGFND_PORT " , AP_PERIPH_RANGEFINDER_PORT_DEFAULT ) ,
2019-10-27 21:31:29 -03:00
2019-10-19 01:36:14 -03:00
// Rangefinder driver
// @Group: RNGFND
2021-04-10 21:01:27 -03:00
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
2019-10-19 01:36:14 -03:00
GOBJECT ( rangefinder , " RNGFND " , RangeFinder ) ,
# endif
2019-11-26 20:06:34 -04:00
# ifdef HAL_PERIPH_ENABLE_ADSB
2021-04-18 19:29:15 -03:00
// @Param: ADSB_BAUDRATE
// @DisplayName: ADSB serial baudrate
// @Description: ADSB serial baudrate.
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000
// @Increment: 1
// @User: Standard
// @RebootRequired: True
2020-01-24 19:59:01 -04:00
GSCALAR ( adsb_baudrate , " ADSB_BAUDRATE " , HAL_PERIPH_ADSB_BAUD_DEFAULT ) ,
2021-04-18 19:29:15 -03:00
// @Param: ADSB_PORT
// @DisplayName: ADSB Serial Port
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to ADSB.
// @Range: 0 10
// @Increment: 1
// @User: Advanced
// @RebootRequired: True
2020-12-17 22:12:25 -04:00
GSCALAR ( adsb_port , " ADSB_PORT " , HAL_PERIPH_ADSB_PORT_DEFAULT ) ,
2019-11-26 20:06:34 -04:00
# endif
2019-12-19 02:21:25 -04:00
# ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT
2021-04-18 19:29:15 -03:00
// @Param: HARDPOINT_ID
// @DisplayName: Hardpoint ID
// @Description: Hardpoint ID
// @User: Advanced
2019-12-19 02:21:25 -04:00
GSCALAR ( hardpoint_id , " HARDPOINT_ID " , HAL_PWM_HARDPOINT_ID_DEFAULT ) ,
2021-04-18 19:29:15 -03:00
// @Param: HARDPOINT_RATE
// @DisplayName: Hardpoint PWM rate
// @Description: Hardpoint PWM rate
// @Range: 10 100
// @Units: Hz
// @Increment: 1
// @User: Advanced
2019-12-19 03:46:03 -04:00
GSCALAR ( hardpoint_rate , " HARDPOINT_RATE " , 100 ) ,
2019-12-19 02:21:25 -04:00
# endif
2020-02-14 01:18:20 -04:00
# ifdef HAL_PERIPH_ENABLE_HWESC
2021-04-18 19:29:15 -03:00
// @Param: ESC_NUMBER
// @DisplayName: ESC number
// @Description: This is the ESC number to report as in UAVCAN ESC telemetry feedback packets.
// @Increment: 1
// @User: Advanced
2020-02-14 01:18:20 -04:00
GSCALAR ( esc_number , " ESC_NUMBER " , 0 ) ,
# endif
2020-11-29 19:14:56 -04:00
2020-12-12 05:08:45 -04:00
# ifdef HAL_PERIPH_ENABLE_RC_OUT
// Servo driver
// @Group: OUT
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
GOBJECT ( servo_channels , " OUT " , SRV_Channels ) ,
2021-03-13 18:56:43 -04:00
2021-04-18 19:29:15 -03:00
// @Param: ESC_PWM_TYPE
// @DisplayName: Output PWM type
// @Description: This selects the output PWM type, allowing for normal PWM continuous output, OneShot, brushed or DShot motor output
2021-12-05 21:05:42 -04:00
// @Values: 1:Normal,2:OneShot,3:OneShot125,4:Brushed,5:DShot150,6:DShot300,7:DShot600,8:DShot1200
2021-04-18 19:29:15 -03:00
// @User: Advanced
// @RebootRequired: True
2021-03-13 18:56:43 -04:00
GSCALAR ( esc_pwm_type , " ESC_PWM_TYPE " , 0 ) ,
2021-12-07 04:09:41 -04:00
2021-12-09 16:30:58 -04:00
# if HAL_WITH_ESC_TELEM && !HAL_GCS_ENABLED
2021-12-07 04:09:41 -04:00
// @Param: ESC_TELEM_PORT
// @DisplayName: ESC Telemetry Serial Port
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to ESC Telemetry
// @Range: 0 10
// @Increment: 1
// @User: Advanced
// @RebootRequired: True
GSCALAR ( esc_telem_port , " ESC_TELEM_PORT " , AP_PERIPH_ESC_TELEM_PORT_DEFAULT ) ,
# endif
2020-12-12 05:08:45 -04:00
# endif
2020-12-26 19:35:15 -04:00
# ifdef HAL_PERIPH_ENABLE_MSP
2021-04-18 19:29:15 -03:00
// @Param: MSP_PORT
// @DisplayName: MSP Serial Port
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to MSP
// @Range: 0 10
// @Increment: 1
// @User: Advanced
// @RebootRequired: True
2020-12-26 19:35:15 -04:00
GSCALAR ( msp_port , " MSP_PORT " , AP_PERIPH_MSP_PORT_DEFAULT ) ,
# endif
2020-12-29 01:06:44 -04:00
# ifdef HAL_PERIPH_ENABLE_NOTIFY
// @Group: NTF_
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
GOBJECT ( notify , " NTF_ " , AP_Notify ) ,
# endif
2021-05-19 23:34:15 -03:00
# if HAL_LOGGING_ENABLED
// @Group: LOG
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
GOBJECT ( logger , " LOG " , AP_Logger ) ,
// @Param: LOG_BITMASK
// @DisplayName: Log bitmask
// @Description: 4 byte bitmap of log types to enable
// @Bitmask: 2:GPS
// @User: Standard
GSCALAR ( log_bitmask , " LOG_BITMASK " , 4 ) ,
# endif
2021-08-18 08:42:18 -03:00
# if HAL_GCS_ENABLED
2021-06-20 03:02:12 -03:00
// @Param: SYSID_THISMAV
// @DisplayName: MAVLink system ID of this vehicle
// @Description: Allows setting an individual system id for this vehicle to distinguish it from others on the same network
// @Range: 1 255
// @User: Advanced
GSCALAR ( sysid_this_mav , " SYSID_THISMAV " , MAV_SYSTEM_ID ) ,
2021-07-11 03:38:42 -03:00
// @Group: SERIAL
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
GOBJECT ( serial_manager , " SERIAL " , AP_SerialManager ) ,
2021-06-20 03:02:12 -03:00
# endif
2021-11-15 01:08:36 -04:00
# if AP_SCRIPTING_ENABLED
2021-09-17 11:33:17 -03:00
// @Group: SCR_
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
GOBJECT ( scripting , " SCR_ " , AP_Scripting ) ,
# endif
2021-05-17 14:26:34 -03:00
2019-05-26 22:46:41 -03:00
AP_VAREND
} ;
void AP_Periph_FW : : load_parameters ( void )
{
AP_Param : : setup_sketch_defaults ( ) ;
if ( ! AP_Param : : check_var_info ( ) ) {
hal . console - > printf ( " Bad parameter table \n " ) ;
AP_HAL : : panic ( " Bad parameter table " ) ;
}
if ( ! g . format_version . load ( ) | |
g . format_version ! = Parameters : : k_format_version ) {
// erase all parameters
StorageManager : : erase ( ) ;
AP_Param : : erase_all ( ) ;
// save the current format version
g . format_version . set_and_save ( Parameters : : k_format_version ) ;
}
// Load all auto-loaded EEPROM variables
AP_Param : : load_all ( ) ;
}