mirror of https://github.com/ArduPilot/ardupilot
AP_Mission: Change jump_to_landing_sequence to get_landing_sequence_start
This commit is contained in:
parent
5ddbcc296d
commit
83c2f497a3
|
@ -1241,16 +1241,17 @@ uint16_t AP_Mission::num_commands_max(void) const
|
|||
}
|
||||
|
||||
// find the nearest landing sequence starting point (DO_LAND_START) and
|
||||
// switch to that mission item.
|
||||
bool AP_Mission::jump_to_landing_sequence()
|
||||
// return its index. Returns 0 if no appropriate DO_LAND_START point can
|
||||
// be found.
|
||||
uint16_t AP_Mission::get_landing_sequence_start()
|
||||
{
|
||||
struct Location current_loc;
|
||||
|
||||
if (!_ahrs.get_position(current_loc)) {
|
||||
return false;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int16_t landing_start_index = -1;
|
||||
uint16_t landing_start_index = 0;
|
||||
float min_distance = -1;
|
||||
|
||||
// Go through mission looking for nearest landing start command
|
||||
|
@ -1268,10 +1269,6 @@ bool AP_Mission::jump_to_landing_sequence()
|
|||
}
|
||||
}
|
||||
|
||||
if (landing_start_index == -1) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return set_current_cmd(landing_start_index);
|
||||
return landing_start_index;
|
||||
}
|
||||
|
||||
|
|
|
@ -321,8 +321,9 @@ public:
|
|||
uint32_t last_change_time_ms(void) const { return _last_change_time_ms; }
|
||||
|
||||
// find the nearest landing sequence starting point (DO_LAND_START) and
|
||||
// switch to that mission item.
|
||||
bool jump_to_landing_sequence();
|
||||
// return its index. Returns 0 if no appropriate DO_LAND_START point can
|
||||
// be found.
|
||||
uint16_t get_landing_sequence_start();
|
||||
|
||||
// user settable parameters
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
|
Loading…
Reference in New Issue