Copter: Remove Armed check from heli RSC controls

This commit is contained in:
Robert Lefebvre 2015-08-12 18:57:33 -04:00 committed by Randy Mackay
parent 535da1d79a
commit c51b57e71c

View File

@ -141,44 +141,39 @@ void Copter::heli_update_rotor_speed_targets()
rsc_control_deglitched = rotor_speed_deglitch_filter.apply(g.rc_8.control_in); rsc_control_deglitched = rotor_speed_deglitch_filter.apply(g.rc_8.control_in);
if (motors.armed()) {
switch (rsc_control_mode) { switch (rsc_control_mode) {
case AP_MOTORS_HELI_RSC_MODE_CH8_PASSTHROUGH: 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 // pass through pilot desired rotor speed if control input is higher than 10, creating a deadband at the bottom
if (rsc_control_deglitched > 10) { if (rsc_control_deglitched > 10) {
motors.set_interlock(true); motors.set_interlock(true);
motors.set_desired_rotor_speed(rsc_control_deglitched); motors.set_desired_rotor_speed(rsc_control_deglitched);
} else { } else {
motors.set_interlock(false); motors.set_interlock(false);
motors.set_desired_rotor_speed(0); motors.set_desired_rotor_speed(0);
} }
break; break;
case AP_MOTORS_HELI_RSC_MODE_SETPOINT: case AP_MOTORS_HELI_RSC_MODE_SETPOINT:
// pass setpoint through as desired rotor speed // pass setpoint through as desired rotor speed
if (rsc_control_deglitched > 0) { if (rsc_control_deglitched > 0) {
motors.set_interlock(true); motors.set_interlock(true);
motors.set_desired_rotor_speed(motors.get_rsc_setpoint()); motors.set_desired_rotor_speed(motors.get_rsc_setpoint());
}else{ }else{
motors.set_interlock(false); motors.set_interlock(false);
motors.set_desired_rotor_speed(0); motors.set_desired_rotor_speed(0);
} }
break; break;
case AP_MOTORS_HELI_RSC_MODE_THROTTLE_CURVE: 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 // 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 // other than being used to create a crude estimate of rotor speed
if (rsc_control_deglitched > 0) { if (rsc_control_deglitched > 0) {
motors.set_interlock(true); motors.set_interlock(true);
motors.set_desired_rotor_speed(motors.get_rsc_setpoint()); motors.set_desired_rotor_speed(motors.get_rsc_setpoint());
}else{ }else{
motors.set_interlock(false); motors.set_interlock(false);
motors.set_desired_rotor_speed(0); motors.set_desired_rotor_speed(0);
} }
break; break;
}
} else {
// if disarmed, force desired_rotor_speed to Zero
motors.set_interlock(false);
motors.set_desired_rotor_speed(0);
} }
// when rotor_runup_complete changes to true, log event // when rotor_runup_complete changes to true, log event