Browse Source

AP_Mission: skip aux function in determining if a takeoff

and reset landing sequenece flag on a takeoff command
apm_2208
Andrew Tridgell 3 years ago
parent
commit
511b0f69f2
  1. 15
      libraries/AP_Mission/AP_Mission.cpp
  2. 3
      libraries/AP_Mission/AP_Mission.h

15
libraries/AP_Mission/AP_Mission.cpp

@ -167,6 +167,7 @@ bool AP_Mission::is_takeoff_next(uint16_t cmd_index) @@ -167,6 +167,7 @@ bool AP_Mission::is_takeoff_next(uint16_t cmd_index)
return true;
// any of these are considered "skippable" when determining if
// we "start with a takeoff command"
case MAV_CMD_DO_AUX_FUNCTION:
case MAV_CMD_NAV_DELAY:
continue;
default:
@ -338,6 +339,8 @@ bool AP_Mission::start_command(const Mission_Command& cmd) @@ -338,6 +339,8 @@ bool AP_Mission::start_command(const Mission_Command& cmd)
// check for landing related commands and set in_landing_sequence flag
if (is_landing_type_cmd(cmd.id) || cmd.id == MAV_CMD_DO_LAND_START) {
set_in_landing_sequence_flag(true);
} else if (is_takeoff_type_cmd(cmd.id)) {
set_in_landing_sequence_flag(false);
}
gcs().send_text(MAV_SEVERITY_INFO, "Mission: %u %s", cmd.index, cmd.type());
@ -2318,6 +2321,18 @@ bool AP_Mission::is_landing_type_cmd(uint16_t id) const @@ -2318,6 +2321,18 @@ bool AP_Mission::is_landing_type_cmd(uint16_t id) const
}
}
// check if command is a takeoff type command.
bool AP_Mission::is_takeoff_type_cmd(uint16_t id) const
{
switch (id) {
case MAV_CMD_NAV_TAKEOFF:
case MAV_CMD_NAV_VTOL_TAKEOFF:
return true;
default:
return false;
}
}
const char *AP_Mission::Mission_Command::type() const
{
switch (id) {

3
libraries/AP_Mission/AP_Mission.h

@ -713,6 +713,9 @@ private: @@ -713,6 +713,9 @@ private:
// check if command is a landing type command. Asside the obvious, MAV_CMD_DO_PARACHUTE is considered a type of landing
bool is_landing_type_cmd(uint16_t id) const;
// check if command is a takeoff type command.
bool is_takeoff_type_cmd(uint16_t id) const;
// approximate the distance travelled to get to a landing. DO_JUMP commands are observed in look forward.
bool distance_to_landing(uint16_t index, float &tot_distance,Location current_loc);

Loading…
Cancel
Save