mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: remove landing.cpp entirely
This commit is contained in:
parent
fc2f518f31
commit
1b0a263761
@ -920,7 +920,6 @@ private:
|
||||
bool geofence_stickmixing(void);
|
||||
void geofence_send_status(mavlink_channel_t chan);
|
||||
bool geofence_breached(void);
|
||||
bool verify_land();
|
||||
void disarm_if_autoland_complete();
|
||||
float tecs_hgt_afe(void);
|
||||
void set_nav_controller(void);
|
||||
|
@ -254,7 +254,13 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
|
||||
return verify_nav_wp(cmd);
|
||||
|
||||
case MAV_CMD_NAV_LAND:
|
||||
return verify_land();
|
||||
{
|
||||
// use rangefinder to correct if possible
|
||||
float height = height_above_target() - rangefinder_correction();
|
||||
|
||||
return landing.verify_land(flight_stage, prev_WP_loc, next_WP_loc, current_loc,
|
||||
auto_state.takeoff_altitude_rel_cm, height, auto_state.sink_rate, auto_state.wp_proportion, auto_state.last_flying_ms, arming.is_armed(), is_flying(), rangefinder_state.in_range, throttle_suppressed);
|
||||
}
|
||||
|
||||
case MAV_CMD_NAV_LOITER_UNLIM:
|
||||
return verify_loiter_unlim();
|
||||
|
@ -1,19 +0,0 @@
|
||||
#include "Plane.h"
|
||||
|
||||
/*
|
||||
landing logic
|
||||
*/
|
||||
|
||||
/*
|
||||
update navigation for landing. Called when on landing approach or
|
||||
final flare
|
||||
*/
|
||||
bool Plane::verify_land()
|
||||
{
|
||||
// use rangefinder to correct if possible
|
||||
float height = height_above_target() - rangefinder_correction();
|
||||
|
||||
return landing.verify_land(flight_stage, prev_WP_loc, next_WP_loc, current_loc,
|
||||
auto_state.takeoff_altitude_rel_cm, height, auto_state.sink_rate, auto_state.wp_proportion, auto_state.last_flying_ms, arming.is_armed(), is_flying(), rangefinder_state.in_range, throttle_suppressed);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user