mirror of https://github.com/ArduPilot/ardupilot
Plane: small arming tidyups
This commit is contained in:
parent
89bbf5de3a
commit
3508a14542
|
@ -690,19 +690,19 @@ static uint16_t mainLoop_count;
|
|||
#if MOUNT == ENABLED
|
||||
// current_loc uses the baro/gps soloution for altitude rather than gps only.
|
||||
// mabe one could use current_loc for lat/lon too and eliminate g_gps alltogether?
|
||||
AP_Mount camera_mount(¤t_loc, g_gps, ahrs, 0);
|
||||
static AP_Mount camera_mount(¤t_loc, g_gps, ahrs, 0);
|
||||
#endif
|
||||
|
||||
#if MOUNT2 == ENABLED
|
||||
// current_loc uses the baro/gps soloution for altitude rather than gps only.
|
||||
// mabe one could use current_loc for lat/lon too and eliminate g_gps alltogether?
|
||||
AP_Mount camera_mount2(¤t_loc, g_gps, ahrs, 1);
|
||||
static AP_Mount camera_mount2(¤t_loc, g_gps, ahrs, 1);
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Arming/Disarming mangement class
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
AP_Arming arming(ahrs, barometer, home_is_set, gcs_send_text_P);
|
||||
static AP_Arming arming(ahrs, barometer, home_is_set, gcs_send_text_P);
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Top-level logic
|
||||
|
@ -775,12 +775,6 @@ void setup() {
|
|||
|
||||
init_ardupilot();
|
||||
|
||||
//if no user intervention require to arm, then just arm already
|
||||
//(maintain old behavior)
|
||||
if (arming.arming_required() == AP_Arming::NO) {
|
||||
arming.arm(AP_Arming::NONE);
|
||||
}
|
||||
|
||||
// initialise the main loop scheduler
|
||||
scheduler.init(&scheduler_tasks[0], sizeof(scheduler_tasks)/sizeof(scheduler_tasks[0]));
|
||||
}
|
||||
|
@ -1083,7 +1077,8 @@ static void update_GPS(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
|
||||
if (!arming.is_armed() ||
|
||||
hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
|
||||
update_home();
|
||||
}
|
||||
}
|
||||
|
|
|
@ -1287,14 +1287,18 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
if (arming.arm(AP_Arming::MAVLINK)) {
|
||||
//only log if arming was successful
|
||||
Log_Arm_Disarm();
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
} else {
|
||||
result = MAV_RESULT_FAILED;
|
||||
}
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
} else if (packet.param1 == 0.0f) {
|
||||
if (arming.disarm()) {
|
||||
//only log if disarming was successful
|
||||
Log_Arm_Disarm();
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
} else {
|
||||
result = MAV_RESULT_FAILED;
|
||||
}
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
} else {
|
||||
result = MAV_RESULT_UNSUPPORTED;
|
||||
}
|
||||
|
|
|
@ -63,12 +63,13 @@ static void init_rc_out()
|
|||
}
|
||||
|
||||
// check for pilot input on rudder stick for arming
|
||||
static void rudder_arm_check() {
|
||||
static void rudder_arm_check()
|
||||
{
|
||||
//TODO: ensure rudder arming disallowed during radio calibration
|
||||
|
||||
//TODO: waggle ailerons and rudder and beep after rudder arming
|
||||
|
||||
static uint32_t rudder_arm_timer = 0;
|
||||
static uint32_t rudder_arm_timer;
|
||||
|
||||
if (arming.is_armed()) {
|
||||
//already armed, no need to run remainder of this function
|
||||
|
@ -82,7 +83,7 @@ static void rudder_arm_check() {
|
|||
}
|
||||
|
||||
//if throttle is not down, then pilot cannot rudder arm
|
||||
if(g.rc_3.control_in > 0 ) {
|
||||
if (g.rc_3.control_in > 0) {
|
||||
rudder_arm_timer = 0;
|
||||
return;
|
||||
}
|
||||
|
@ -95,12 +96,12 @@ static void rudder_arm_check() {
|
|||
|
||||
// full left or right rudder starts arming counter
|
||||
if (g.rc_4.control_in > 4000
|
||||
|| g.rc_4.control_in < -4000) {
|
||||
|| g.rc_4.control_in < -4000) {
|
||||
|
||||
uint32_t now = millis();
|
||||
|
||||
if (rudder_arm_timer == 0 ||
|
||||
now - rudder_arm_timer < 3000) {
|
||||
now - rudder_arm_timer < 3000) {
|
||||
|
||||
if (rudder_arm_timer == 0) rudder_arm_timer = now;
|
||||
} else {
|
||||
|
|
Loading…
Reference in New Issue