Skip to content

Commit

Permalink
AP_Arming: move arming delay logic into AP_Arming_Plane
Browse files Browse the repository at this point in the history
  • Loading branch information
kd0aij committed Jun 16, 2020
1 parent d374b66 commit 0efee79
Show file tree
Hide file tree
Showing 2 changed files with 17 additions and 1 deletion.
13 changes: 12 additions & 1 deletion ArduPlane/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
#include "AP_Arming.h"
#include "Plane.h"

constexpr uint32_t AP_ARMING_DELAY_MS = 2000; // delay from arming to start of motor spoolup

const AP_Param::GroupInfo AP_Arming_Plane::var_info[] = {
// variables from parent vehicle
AP_NESTEDGROUPINFO(AP_Arming, 0),
Expand Down Expand Up @@ -180,7 +182,9 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c
}

change_arm_state();
plane.quadplane.delay_arming = true;

// rising edge of delay_arming oneshot
delay_arming = true;

gcs().send_text(MAV_SEVERITY_INFO, "Throttle armed");

Expand Down Expand Up @@ -234,5 +238,12 @@ void AP_Arming_Plane::update_soft_armed()
hal.util->set_soft_armed(is_armed() &&
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED);
AP::logger().set_vehicle_armed(hal.util->get_soft_armed());

// update delay_arming oneshot
if (delay_arming &&
(AP_HAL::millis() - hal.util->get_last_armed_change() >= AP_ARMING_DELAY_MS)) {

delay_arming = false;
}
}

5 changes: 5 additions & 0 deletions ArduPlane/AP_Arming.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,10 +28,15 @@ class AP_Arming_Plane : public AP_Arming
bool arm(AP_Arming::Method method, bool do_arming_checks=true) override;

void update_soft_armed();
bool get_delay_arming() { return delay_arming; };

protected:
bool ins_checks(bool report) override;

private:
void change_arm_state(void);

// oneshot with duration AP_ARMING_DELAY_MS used by quadplane to delay spoolup after arming:
// ignored unless OPTION_DELAY_ARMING or OPTION_TILT_DISARMED is set
bool delay_arming;
};

0 comments on commit 0efee79

Please sign in to comment.