mirror of https://github.com/ArduPilot/ardupilot
ArduCopter - motors.pde - changed references to "motor_armed" to "motors.armed()" because we've moved to using the AP_Motors class.
Simplified set_servos_4 function which was responsible for calling "output_motors_armed" or "output_motors_disarmed" as this determination as to whether the motors are armed or not is handled within the AP_Motors class.
This commit is contained in:
parent
00d540bfa9
commit
0f4203a755
|
@ -26,7 +26,7 @@ static void arm_motors()
|
|||
arming_counter = 0;
|
||||
|
||||
}else if (arming_counter == ARM_DELAY){
|
||||
if(motor_armed == false){
|
||||
if(motors.armed() == false){
|
||||
// arm the motors and configure for flight
|
||||
init_arm_motors();
|
||||
}
|
||||
|
@ -46,7 +46,7 @@ static void arm_motors()
|
|||
arming_counter = 0;
|
||||
|
||||
}else if (arming_counter == DISARM_DELAY){
|
||||
if(motor_armed == true){
|
||||
if(motors.armed()){
|
||||
// arm the motors and configure for flight
|
||||
init_disarm_motors();
|
||||
}
|
||||
|
@ -82,8 +82,7 @@ static void init_arm_motors()
|
|||
if (gcs3.initialised) {
|
||||
Serial3.set_blocking_writes(false);
|
||||
}
|
||||
|
||||
motor_armed = true;
|
||||
motors.armed(true);
|
||||
|
||||
#if PIEZO_ARMING == 1
|
||||
piezo_beep();
|
||||
|
@ -130,7 +129,7 @@ static void init_disarm_motors()
|
|||
gcs_send_text_P(SEVERITY_HIGH, PSTR("DISARMING MOTORS"));
|
||||
#endif
|
||||
|
||||
motor_armed = false;
|
||||
motors.armed(false);
|
||||
compass.save_offsets();
|
||||
|
||||
g.throttle_cruise.save();
|
||||
|
@ -149,25 +148,6 @@ static void init_disarm_motors()
|
|||
static void
|
||||
set_servos_4()
|
||||
{
|
||||
if (motor_armed == true && motor_auto_armed == true) {
|
||||
// creates the radio_out and pwm_out values
|
||||
output_motors_armed();
|
||||
} else{
|
||||
output_motors_disarmed();
|
||||
}
|
||||
}
|
||||
|
||||
int ch_of_mot( int mot ) {
|
||||
switch (mot) {
|
||||
case 1: return MOT_1;
|
||||
case 2: return MOT_2;
|
||||
case 3: return MOT_3;
|
||||
case 4: return MOT_4;
|
||||
case 5: return MOT_5;
|
||||
case 6: return MOT_6;
|
||||
case 7: return MOT_7;
|
||||
case 8: return MOT_8;
|
||||
}
|
||||
return (-1);
|
||||
motors.output();
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue