AP_Landing: remove SpdHgt and use TECS direct

This commit is contained in:
Iampete1 2021-11-12 17:54:43 +00:00 committed by Andrew Tridgell
parent 29455adab4
commit 1c195d01b8
4 changed files with 8 additions and 9 deletions

View File

@ -164,7 +164,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
};
// constructor
AP_Landing::AP_Landing(AP_Mission &_mission, AP_AHRS &_ahrs, AP_SpdHgtControl *_SpdHgt_Controller, AP_Navigation *_nav_controller, AP_Vehicle::FixedWing &_aparm,
AP_Landing::AP_Landing(AP_Mission &_mission, AP_AHRS &_ahrs, AP_TECS *_tecs_Controller, AP_Navigation *_nav_controller, AP_Vehicle::FixedWing &_aparm,
set_target_altitude_proportion_fn_t _set_target_altitude_proportion_fn,
constrain_target_altitude_location_fn_t _constrain_target_altitude_location_fn,
adjusted_altitude_cm_fn_t _adjusted_altitude_cm_fn,
@ -173,7 +173,7 @@ AP_Landing::AP_Landing(AP_Mission &_mission, AP_AHRS &_ahrs, AP_SpdHgtControl *_
update_flight_stage_fn_t _update_flight_stage_fn) :
mission(_mission)
,ahrs(_ahrs)
,SpdHgt_Controller(_SpdHgt_Controller)
,tecs_Controller(_tecs_Controller)
,nav_controller(_nav_controller)
,aparm(_aparm)
,set_target_altitude_proportion_fn(_set_target_altitude_proportion_fn)
@ -577,7 +577,7 @@ int32_t AP_Landing::get_target_airspeed_cm(void)
// don't return the landing airspeed, because if type is invalid we have
// no postive indication that the land airspeed has been configured or
// how it was meant to be utilized
return SpdHgt_Controller->get_target_airspeed();
return tecs_Controller->get_target_airspeed();
}
}

View File

@ -18,7 +18,7 @@
#include <AP_Param/AP_Param.h>
#include <AP_Mission/AP_Mission.h>
#include <AP_Common/AP_Common.h>
#include <AP_SpdHgtControl/AP_SpdHgtControl.h>
#include <AP_TECS/AP_TECS.h>
#include <AP_Navigation/AP_Navigation.h>
#include "AP_Landing_Deepstall.h"
#include <AP_Common/Location.h>
@ -36,7 +36,7 @@ public:
FUNCTOR_TYPEDEF(disarm_if_autoland_complete_fn_t, void);
FUNCTOR_TYPEDEF(update_flight_stage_fn_t, void);
AP_Landing(AP_Mission &_mission, AP_AHRS &_ahrs, AP_SpdHgtControl *_SpdHgt_Controller, AP_Navigation *_nav_controller, AP_Vehicle::FixedWing &_aparm,
AP_Landing(AP_Mission &_mission, AP_AHRS &_ahrs, AP_TECS *_tecs_Controller, AP_Navigation *_nav_controller, AP_Vehicle::FixedWing &_aparm,
set_target_altitude_proportion_fn_t _set_target_altitude_proportion_fn,
constrain_target_altitude_location_fn_t _constrain_target_altitude_location_fn,
adjusted_altitude_cm_fn_t _adjusted_altitude_cm_fn,
@ -135,7 +135,7 @@ private:
AP_Mission &mission;
AP_AHRS &ahrs;
AP_SpdHgtControl *SpdHgt_Controller;
AP_TECS *tecs_Controller;
AP_Navigation *nav_controller;
AP_Vehicle::FixedWing &aparm;

View File

@ -18,7 +18,6 @@
#include <AP_Param/AP_Param.h>
#include <AP_Mission/AP_Mission.h>
#include <AP_Common/AP_Common.h>
#include <AP_SpdHgtControl/AP_SpdHgtControl.h>
#include <AP_Navigation/AP_Navigation.h>
#include <PID/PID.h>

View File

@ -283,7 +283,7 @@ void AP_Landing::type_slope_setup_landing_glide_slope(const Location &prev_WP_lo
}
// time before landing that we will flare
float flare_time = aim_height / SpdHgt_Controller->get_land_sinkrate();
float flare_time = aim_height / tecs_Controller->get_land_sinkrate();
// distance to flare is based on ground speed, adjusted as we
// get closer. This takes into account the wind
@ -334,7 +334,7 @@ int32_t AP_Landing::type_slope_get_target_airspeed_cm(void)
// we're landing, check for custom approach and
// pre-flare airspeeds. Also increase for head-winds
const float land_airspeed = SpdHgt_Controller->get_land_airspeed();
const float land_airspeed = tecs_Controller->get_land_airspeed();
int32_t target_airspeed_cm = aparm.airspeed_cruise_cm;
switch (type_slope_stage) {