Copter: Remove Armed check from heli RSC controls
This commit is contained in:
parent
535da1d79a
commit
c51b57e71c
@ -141,44 +141,39 @@ void Copter::heli_update_rotor_speed_targets()
|
||||
|
||||
rsc_control_deglitched = rotor_speed_deglitch_filter.apply(g.rc_8.control_in);
|
||||
|
||||
if (motors.armed()) {
|
||||
switch (rsc_control_mode) {
|
||||
case AP_MOTORS_HELI_RSC_MODE_CH8_PASSTHROUGH:
|
||||
// pass through pilot desired rotor speed if control input is higher than 10, creating a deadband at the bottom
|
||||
if (rsc_control_deglitched > 10) {
|
||||
motors.set_interlock(true);
|
||||
motors.set_desired_rotor_speed(rsc_control_deglitched);
|
||||
} else {
|
||||
motors.set_interlock(false);
|
||||
motors.set_desired_rotor_speed(0);
|
||||
}
|
||||
break;
|
||||
case AP_MOTORS_HELI_RSC_MODE_SETPOINT:
|
||||
// pass setpoint through as desired rotor speed
|
||||
if (rsc_control_deglitched > 0) {
|
||||
motors.set_interlock(true);
|
||||
motors.set_desired_rotor_speed(motors.get_rsc_setpoint());
|
||||
}else{
|
||||
motors.set_interlock(false);
|
||||
motors.set_desired_rotor_speed(0);
|
||||
}
|
||||
break;
|
||||
case AP_MOTORS_HELI_RSC_MODE_THROTTLE_CURVE:
|
||||
// pass setpoint through as desired rotor speed, this is almost pointless as the Setpoint serves no function in this mode
|
||||
// other than being used to create a crude estimate of rotor speed
|
||||
if (rsc_control_deglitched > 0) {
|
||||
motors.set_interlock(true);
|
||||
motors.set_desired_rotor_speed(motors.get_rsc_setpoint());
|
||||
}else{
|
||||
motors.set_interlock(false);
|
||||
motors.set_desired_rotor_speed(0);
|
||||
}
|
||||
break;
|
||||
}
|
||||
} else {
|
||||
// if disarmed, force desired_rotor_speed to Zero
|
||||
motors.set_interlock(false);
|
||||
motors.set_desired_rotor_speed(0);
|
||||
|
||||
switch (rsc_control_mode) {
|
||||
case AP_MOTORS_HELI_RSC_MODE_CH8_PASSTHROUGH:
|
||||
// pass through pilot desired rotor speed if control input is higher than 10, creating a deadband at the bottom
|
||||
if (rsc_control_deglitched > 10) {
|
||||
motors.set_interlock(true);
|
||||
motors.set_desired_rotor_speed(rsc_control_deglitched);
|
||||
} else {
|
||||
motors.set_interlock(false);
|
||||
motors.set_desired_rotor_speed(0);
|
||||
}
|
||||
break;
|
||||
case AP_MOTORS_HELI_RSC_MODE_SETPOINT:
|
||||
// pass setpoint through as desired rotor speed
|
||||
if (rsc_control_deglitched > 0) {
|
||||
motors.set_interlock(true);
|
||||
motors.set_desired_rotor_speed(motors.get_rsc_setpoint());
|
||||
}else{
|
||||
motors.set_interlock(false);
|
||||
motors.set_desired_rotor_speed(0);
|
||||
}
|
||||
break;
|
||||
case AP_MOTORS_HELI_RSC_MODE_THROTTLE_CURVE:
|
||||
// pass setpoint through as desired rotor speed, this is almost pointless as the Setpoint serves no function in this mode
|
||||
// other than being used to create a crude estimate of rotor speed
|
||||
if (rsc_control_deglitched > 0) {
|
||||
motors.set_interlock(true);
|
||||
motors.set_desired_rotor_speed(motors.get_rsc_setpoint());
|
||||
}else{
|
||||
motors.set_interlock(false);
|
||||
motors.set_desired_rotor_speed(0);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
// when rotor_runup_complete changes to true, log event
|
||||
|
Loading…
Reference in New Issue
Block a user