mirror of https://github.com/ArduPilot/ardupilot
Copter: remove unnecessary control_mode_t casts
Thanks @OXINARF
This commit is contained in:
parent
8f41215569
commit
55ffee25b1
|
@ -111,12 +111,12 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason)
|
|||
// update flight mode
|
||||
if (success) {
|
||||
// perform any cleanup required by previous flight mode
|
||||
exit_mode(control_mode, (control_mode_t)mode);
|
||||
exit_mode(control_mode, mode);
|
||||
|
||||
prev_control_mode = control_mode;
|
||||
prev_control_mode_reason = control_mode_reason;
|
||||
|
||||
control_mode = (control_mode_t)mode;
|
||||
control_mode = mode;
|
||||
control_mode_reason = reason;
|
||||
DataFlash.Log_Write_Mode(control_mode, control_mode_reason);
|
||||
|
||||
|
|
Loading…
Reference in New Issue