mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: refactor KILL_IMU of do_aux_function
This commit is contained in:
parent
6f81c250be
commit
e63918d9ba
|
@ -1097,19 +1097,11 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
|
|||
|
||||
#if !HAL_MINIMIZE_FEATURES
|
||||
case AUX_FUNC::KILL_IMU1:
|
||||
if (ch_flag == AuxSwitchPos::HIGH) {
|
||||
AP::ins().kill_imu(0, true);
|
||||
} else {
|
||||
AP::ins().kill_imu(0, false);
|
||||
}
|
||||
AP::ins().kill_imu(0, ch_flag == AuxSwitchPos::HIGH);
|
||||
break;
|
||||
|
||||
case AUX_FUNC::KILL_IMU2:
|
||||
if (ch_flag == AuxSwitchPos::HIGH) {
|
||||
AP::ins().kill_imu(1, true);
|
||||
} else {
|
||||
AP::ins().kill_imu(1, false);
|
||||
}
|
||||
AP::ins().kill_imu(1, ch_flag == AuxSwitchPos::HIGH);
|
||||
break;
|
||||
#endif // HAL_MINIMIZE_FEATURES
|
||||
|
||||
|
|
Loading…
Reference in New Issue