mirror of https://github.com/ArduPilot/ardupilot
Rover: remove redundant SYS_NUM_RESETS
this is handled by AP_Stats library
This commit is contained in:
parent
e2d4182c75
commit
6eceaef484
|
@ -31,13 +31,6 @@ const AP_Param::Info Rover::var_info[] = {
|
|||
// @User: Advanced
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
||||
|
||||
// @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: RST_SWITCH_CH
|
||||
// @DisplayName: Reset Switch Channel
|
||||
// @Description: RC channel to use to reset to last flight mode after geofence takeover.
|
||||
|
|
|
@ -27,7 +27,7 @@ public:
|
|||
// Misc
|
||||
//
|
||||
k_param_log_bitmask_old = 10, // unused
|
||||
k_param_num_resets,
|
||||
k_param_num_resets_old, // unused
|
||||
k_param_reset_switch_chan,
|
||||
k_param_initial_mode,
|
||||
k_param_scheduler,
|
||||
|
@ -212,7 +212,6 @@ public:
|
|||
// Misc
|
||||
//
|
||||
AP_Int32 log_bitmask;
|
||||
AP_Int16 num_resets;
|
||||
AP_Int8 reset_switch_chan;
|
||||
AP_Int8 initial_mode;
|
||||
|
||||
|
|
|
@ -66,10 +66,6 @@ void Rover::init_ardupilot()
|
|||
|
||||
rssi.init();
|
||||
|
||||
// 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 before we start the GCS, so that the CLI baro test works
|
||||
barometer.init();
|
||||
|
||||
|
|
Loading…
Reference in New Issue