Copter: initial creation of motor_interlock

This commit is contained in:
Robert Lefebvre 2015-03-10 22:10:02 -04:00 committed by Randy Mackay
parent ee94db09a8
commit e4c5915330
5 changed files with 20 additions and 0 deletions

View File

@ -139,3 +139,10 @@ void set_pre_arm_rc_check(bool b)
}
}
void set_motor_interlock(bool b)
{
if(ap.motor_interlock != b) {
ap.motor_interlock = b;
}
}

View File

@ -357,6 +357,7 @@ static union {
uint8_t system_time_set : 1; // 28 // true if the system time has been set from the GPS
uint8_t gps_base_pos_set : 1; // 29 // true when the gps base position has been set (used for RTK gps only)
enum HomeState home_state : 2; // 30,31 // home status (unset, set, locked)
uint8_t motor_interlock : 1; // 32 // motor interlock status, final control for motors on/off
};
uint32_t value;
} ap;

View File

@ -66,6 +66,7 @@ enum aux_sw_func {
AUXSW_RELAY, // Relay pin on/off (only supports first relay)
AUXSW_LANDING_GEAR, // Landing gear controller
AUXSW_LOST_COPTER_SOUND, // Play lost copter sound
AUXSW_MOTOR_INTERLOCK, // Motor On/Off switch
};
// Frame types

View File

@ -686,6 +686,10 @@ static void init_disarm_motors()
gcs_send_text_P(SEVERITY_HIGH, PSTR("DISARMING MOTORS"));
#endif
// always force Motor Interlock to false
set_motor_interlock(false);
// send disarm command to motors
motors.armed(false);
// save compass offsets learned by the EKF

View File

@ -545,6 +545,13 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
break;
}
break;
case AUXSW_MOTOR_INTERLOCK:
// Turn on when above LOW, because channel will also be used for speed
// control signal in tradheli
set_motor_interlock(ch_flag == AUX_SWITCH_HIGH || ch_flag == AUX_SWITCH_MIDDLE);
break;
}
}