Copter: Helicopters to use motor interlock logic.

Also, remove motor interlock pre-arm check to streamline logic.
This commit is contained in:
Robert Lefebvre 2015-08-02 21:17:53 -04:00 committed by Randy Mackay
parent 161ce5c11d
commit c968ec3a63
2 changed files with 24 additions and 11 deletions

View File

@ -16,7 +16,8 @@ static int8_t heli_dynamic_flight_counter;
// heli_init - perform any special initialisation required for the tradheli
void Copter::heli_init()
{
// Nothing in here for now. To-Do: Eliminate this function completely?
// helicopters are always using motor interlock
set_using_interlock(true);
}
// get_pilot_desired_collective - converts pilot input (from 0 ~ 1000) to a value that can be fed into the channel_throttle->servo_out function
@ -142,24 +143,30 @@ void Copter::heli_update_rotor_speed_targets()
if (motors.armed()) {
switch (rsc_control_mode) {
case AP_MOTORS_HELI_RSC_MODE_NONE:
// even though pilot passes rotors speed directly to rotor ESC via receiver, motor lib needs to know if
// rotor is spinning in case we are using direct drive tailrotor which must be spun up at same time
case AP_MOTORS_HELI_RSC_MODE_CH8_PASSTHROUGH:
// pass through pilot desired rotor speed
motors.set_desired_rotor_speed(rsc_control_deglitched);
// 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;
}
} else {
// if disarmed, force desired_rotor_speed to Zero
motors.set_interlock(false);
motors.set_desired_rotor_speed(0);
}

View File

@ -85,9 +85,11 @@ void Copter::auto_disarm_check()
// always allow auto disarm if using interlock switch or motors are Emergency Stopped
if ((ap.using_interlock && !motors.get_interlock()) || ap.motor_emergency_stop) {
auto_disarming_counter++;
#if FRAME_CONFIG != HELI_FRAME
// use a shorter delay if using throttle interlock switch or Emergency Stop, because it is less
// obvious the copter is armed as the motors will not be spinning
disarm_delay /= 2;
#endif
} else {
bool sprung_throttle_stick = (g.throttle_behavior & THR_BEHAVE_FEEDBACK_FROM_MID_STICK) != 0;
bool thr_low;
@ -184,8 +186,13 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
did_ground_start = true;
}
#if FRAME_CONFIG == HELI_FRAME
// helicopters are always using motor interlock
set_using_interlock(true);
#else
// check if we are using motor interlock control on an aux switch
set_using_interlock(check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK));
#endif
// if we are using motor interlock switch and it's enabled, fail to arm
if (ap.using_interlock && motors.get_interlock()){
@ -739,13 +746,12 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
return false;
}
// always check if rotor is spinning on heli
#if FRAME_CONFIG == HELI_FRAME
// heli specific arming check
if ((rsc_control_deglitched > 0) || !motors.allow_arming()){
#if FRAME_CONFIG == HELI_FRAME
// check if rotor is spinning on heli because this could disrupt gyro calibration
if (!motors.allow_arming()){
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Rotor Control Engaged"));
}
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Rotor is Spinning")); }
return false;
}
#endif // HELI_FRAME