mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: create define specifically for the developer feature for killing IMUs
This commit is contained in:
parent
baf5d34256
commit
3517884002
|
@ -679,9 +679,11 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPo
|
||||||
#if AP_GRIPPER_ENABLED
|
#if AP_GRIPPER_ENABLED
|
||||||
case AUX_FUNC::GRIPPER:
|
case AUX_FUNC::GRIPPER:
|
||||||
#endif
|
#endif
|
||||||
|
#if AP_INERTIALSENSOR_KILL_IMU_ENABLED
|
||||||
case AUX_FUNC::KILL_IMU1:
|
case AUX_FUNC::KILL_IMU1:
|
||||||
case AUX_FUNC::KILL_IMU2:
|
case AUX_FUNC::KILL_IMU2:
|
||||||
case AUX_FUNC::KILL_IMU3:
|
case AUX_FUNC::KILL_IMU3:
|
||||||
|
#endif
|
||||||
case AUX_FUNC::MISSION_RESET:
|
case AUX_FUNC::MISSION_RESET:
|
||||||
case AUX_FUNC::MOTOR_ESTOP:
|
case AUX_FUNC::MOTOR_ESTOP:
|
||||||
case AUX_FUNC::RC_OVERRIDE_ENABLE:
|
case AUX_FUNC::RC_OVERRIDE_ENABLE:
|
||||||
|
@ -1440,7 +1442,7 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if !HAL_MINIMIZE_FEATURES
|
#if AP_INERTIALSENSOR_KILL_IMU_ENABLED
|
||||||
case AUX_FUNC::KILL_IMU1:
|
case AUX_FUNC::KILL_IMU1:
|
||||||
AP::ins().kill_imu(0, ch_flag == AuxSwitchPos::HIGH);
|
AP::ins().kill_imu(0, ch_flag == AuxSwitchPos::HIGH);
|
||||||
break;
|
break;
|
||||||
|
@ -1452,7 +1454,7 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos
|
||||||
case AUX_FUNC::KILL_IMU3:
|
case AUX_FUNC::KILL_IMU3:
|
||||||
AP::ins().kill_imu(2, ch_flag == AuxSwitchPos::HIGH);
|
AP::ins().kill_imu(2, ch_flag == AuxSwitchPos::HIGH);
|
||||||
break;
|
break;
|
||||||
#endif // HAL_MINIMIZE_FEATURES
|
#endif // AP_INERTIALSENSOR_KILL_IMU_ENABLED
|
||||||
|
|
||||||
#if AP_CAMERA_ENABLED
|
#if AP_CAMERA_ENABLED
|
||||||
case AUX_FUNC::CAMERA_TRIGGER:
|
case AUX_FUNC::CAMERA_TRIGGER:
|
||||||
|
|
Loading…
Reference in New Issue