Now for Arming/Disarming motors you should wait 2 seconds (security feature to prevent disarming during flight)

git-svn-id: https://arducopter.googlecode.com/svn/trunk@73 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jjulio1234 2010-08-11 20:43:12 +00:00
parent 4af9be6e85
commit 83c5e06025
1 changed files with 26 additions and 5 deletions

View File

@ -227,6 +227,10 @@ int minThrottle = 0;
char queryType;
long tlmTimer = 0;
// Arming/Disarming
uint8_t Arming_counter=0;
uint8_t Disarming_counter=0;
/* ************************************************************ */
/* Altitude control... (based on sonar) */
void Altitude_control(int target_sonar_altitude)
@ -725,19 +729,36 @@ void loop(){
command_rx_yaw_diff = 0;
}
// Arm motor output
// Arm motor output : Throttle down and full yaw right for more than 2 seconds
if (ch_throttle < 1200) {
control_yaw = 0;
command_rx_yaw = ToDeg(yaw);
command_rx_yaw_diff = 0;
if (ch_yaw > 1800) {
motorArmed = 1;
minThrottle = 1100;
if (Arming_counter>240){
motorArmed = 1;
minThrottle = 1100;
}
else
Arming_counter++;
}
else
Arming_counter=0;
// To Disarm motor output : Throttle down and full yaw left for more than 2 seconds
if (ch_yaw < 1200) {
motorArmed = 0;
minThrottle = MIN_THROTTLE;
if (Disarming_counter>240){
motorArmed = 0;
minThrottle = MIN_THROTTLE;
}
else
Disarming_counter++;
}
else
Disarming_counter=0;
}
else{
Arming_counter=0;
Disarming_counter=0;
}
// Quadcopter mix