Plane: remove SYS_NUM_RESETS, replaced by STAT_BOOTCNT

This commit is contained in:
Iampete1 2023-06-19 23:24:36 +01:00 committed by Andrew Tridgell
parent b153a90430
commit 2f4b617464
3 changed files with 1 additions and 13 deletions

View File

@ -605,13 +605,6 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Standard
GSCALAR(dspoiler_rud_rate, "DSPOILR_RUD_RATE", DSPOILR_RUD_RATE_DEFAULT),
// @Param: SYS_NUM_RESETS
// @DisplayName: Num Resets
// @Description: Number of APM board resets
// @ReadOnly: True
// @User: Advanced
GSCALAR(num_resets, "SYS_NUM_RESETS", 0),
// @Param: LOG_BITMASK
// @DisplayName: Log bitmask
// @Description: Bitmap of what on-board log types to enable. This value is made up of the sum of each of the log types you want to be saved. It is usually best just to enable all basic log types by setting this to 65535.

View File

@ -43,7 +43,7 @@ public:
//
k_param_format_version = 0,
k_param_software_type, // unused;
k_param_num_resets,
k_param_num_resets, // unused
k_param_NavEKF2,
k_param_g2,
k_param_avoidance_adsb,
@ -434,7 +434,6 @@ public:
AP_Float mixing_gain;
AP_Int16 mixing_offset;
AP_Int16 dspoiler_rud_rate;
AP_Int16 num_resets;
AP_Int32 log_bitmask;
AP_Int32 RTL_altitude_cm;
AP_Int16 pitch_trim_cd;

View File

@ -51,10 +51,6 @@ void Plane::init_ardupilot()
notify_mode(*control_mode);
init_rc_out_main();
// keep a record of how many resets have happened. This can be
// used to detect in-flight resets
g.num_resets.set_and_save(g.num_resets+1);
// init baro
barometer.init();