Browse Source

Plane: allow landing height adjustment on wp before land (aka approach wp)

master
Tom Pittenger 9 years ago
parent
commit
26efd90603
  1. 3
      ArduPlane/Plane.h
  2. 3
      ArduPlane/altitude.cpp
  3. 4
      ArduPlane/commands_logic.cpp

3
ArduPlane/Plane.h

@ -442,6 +442,9 @@ private: @@ -442,6 +442,9 @@ private:
// are we in auto and flight mode is approach || pre-flare || final (flare)
bool land_in_progress:1;
// are we headed to the land approach waypoint? Works for any nav type
bool wp_is_land_approach:1;
// should we fly inverted?
bool inverted_flight:1;

3
ArduPlane/altitude.cpp

@ -474,7 +474,8 @@ int32_t Plane::adjusted_relative_altitude_cm(void) @@ -474,7 +474,8 @@ int32_t Plane::adjusted_relative_altitude_cm(void)
float Plane::mission_alt_offset(void)
{
float ret = g.alt_offset;
if (control_mode == AUTO && auto_state.land_in_progress) {
if (control_mode == AUTO &&
(auto_state.land_in_progress || auto_state.wp_is_land_approach)) {
// when landing after an aborted landing due to too high glide
// slope we use an offset from the last landing attempt
ret += auto_state.land_alt_offset;

4
ArduPlane/commands_logic.cpp

@ -40,6 +40,10 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) @@ -40,6 +40,10 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
// reset loiter start time. New command is a new loiter
loiter.start_time_ms = 0;
AP_Mission::Mission_Command next_nav_cmd;
const uint16_t next_index = mission.get_current_nav_index() + 1;
auto_state.wp_is_land_approach = mission.get_next_nav_cmd(next_index, next_nav_cmd) && (next_nav_cmd.id == MAV_CMD_NAV_LAND);
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Executing nav command ID #%i",cmd.id);
} else {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Executing command ID #%i",cmd.id);

Loading…
Cancel
Save