mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Sub: remove unused prev_control_mode_reason
This commit is contained in:
parent
f854477efe
commit
82edfc6237
@ -216,7 +216,6 @@ private:
|
|||||||
control_mode_t control_mode;
|
control_mode_t control_mode;
|
||||||
|
|
||||||
control_mode_t prev_control_mode;
|
control_mode_t prev_control_mode;
|
||||||
ModeReason prev_control_mode_reason = ModeReason::UNKNOWN;
|
|
||||||
|
|
||||||
#if RCMAP_ENABLED == ENABLED
|
#if RCMAP_ENABLED == ENABLED
|
||||||
RCMapper rcmap;
|
RCMapper rcmap;
|
||||||
|
@ -10,7 +10,6 @@ bool Sub::set_mode(control_mode_t mode, ModeReason reason)
|
|||||||
// return immediately if we are already in the desired mode
|
// return immediately if we are already in the desired mode
|
||||||
if (mode == control_mode) {
|
if (mode == control_mode) {
|
||||||
prev_control_mode = control_mode;
|
prev_control_mode = control_mode;
|
||||||
prev_control_mode_reason = control_mode_reason;
|
|
||||||
|
|
||||||
control_mode_reason = reason;
|
control_mode_reason = reason;
|
||||||
return true;
|
return true;
|
||||||
@ -70,7 +69,6 @@ bool Sub::set_mode(control_mode_t mode, ModeReason reason)
|
|||||||
exit_mode(control_mode, mode);
|
exit_mode(control_mode, mode);
|
||||||
|
|
||||||
prev_control_mode = control_mode;
|
prev_control_mode = control_mode;
|
||||||
prev_control_mode_reason = control_mode_reason;
|
|
||||||
|
|
||||||
control_mode = mode;
|
control_mode = mode;
|
||||||
control_mode_reason = reason;
|
control_mode_reason = reason;
|
||||||
|
Loading…
Reference in New Issue
Block a user