Skip to content

Commit

Permalink
ArduCopter: create land_complete callback on Mode
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Apr 7, 2024
1 parent 4d88d9e commit 914e81d
Show file tree
Hide file tree
Showing 3 changed files with 30 additions and 6 deletions.
8 changes: 2 additions & 6 deletions ArduCopter/land_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,13 +156,9 @@ void Copter::set_land_complete(bool b)

// tell AHRS flying state
set_likely_flying(!b);

// trigger disarm-on-land if configured
bool disarm_on_land_configured = (g.throttle_behavior & THR_BEHAVE_DISARM_ON_LAND_DETECT) != 0;
const bool mode_disarms_on_land = flightmode->allows_arming(AP_Arming::Method::LANDING) && !flightmode->has_manual_throttle();

if (ap.land_complete && motors->armed() && disarm_on_land_configured && mode_disarms_on_land) {
arming.disarm(AP_Arming::Method::LANDED);
if (b) {
flightmode->land_complete();
}
}

Expand Down
25 changes: 25 additions & 0 deletions ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -472,6 +472,31 @@ void Copter::notify_flight_mode() {
notify.set_flight_mode_str(flightmode->name4());
}

// called when the land detector determines we are landed:
void Mode::land_complete()
{
// trigger disarm-on-land if configured
if ((g.throttle_behavior & THR_BEHAVE_DISARM_ON_LAND_DETECT) == 0) {
// not configured to disarm
return;
}

if (!motors->armed()) {
// not armed
return;
}

if (has_manual_throttle()) {
return;
}
// we should probably have a "allows_disarm(...)" callback
if (!allows_arming(AP_Arming::Method::LANDING)) {
return;
}

AP::arming().disarm(AP_Arming::Method::LANDED);
}

// get_pilot_desired_angle - transform pilot's roll or pitch input into a desired lean angle
// returns desired angle in centi-degrees
void Mode::get_pilot_desired_lean_angles(float &roll_out_cd, float &pitch_out_cd, float angle_max_cd, float angle_limit_cd) const
Expand Down
3 changes: 3 additions & 0 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,9 @@ class Mode {

virtual bool is_landing() const { return false; }

// called when the land detector determines we are landed:
void land_complete();

// mode requires terrain to be present to be functional
virtual bool requires_terrain_failsafe() const { return false; }

Expand Down

0 comments on commit 914e81d

Please sign in to comment.