AP_Landing: add static create method

This commit is contained in:
Lucas De Marchi 2017-08-30 12:05:07 -07:00 committed by Francisco Ferreira
parent e98ccb9ae6
commit c745908b14
1 changed files with 25 additions and 6 deletions

View File

@ -25,11 +25,10 @@
/// @class AP_Landing
/// @brief Class managing ArduPlane landing methods
class AP_Landing
{
public:
class AP_Landing {
friend class AP_Landing_Deepstall;
public:
FUNCTOR_TYPEDEF(set_target_altitude_proportion_fn_t, void, const Location&, float);
FUNCTOR_TYPEDEF(constrain_target_altitude_location_fn_t, void, const Location&, const Location&);
FUNCTOR_TYPEDEF(adjusted_altitude_cm_fn_t, int32_t);
@ -37,14 +36,27 @@ public:
FUNCTOR_TYPEDEF(disarm_if_autoland_complete_fn_t, void);
FUNCTOR_TYPEDEF(update_flight_stage_fn_t, void);
// constructor
AP_Landing(AP_Mission &_mission, AP_AHRS &_ahrs, AP_SpdHgtControl *_SpdHgt_Controller, AP_Navigation *_nav_controller, AP_Vehicle::FixedWing &_aparm,
static AP_Landing create(AP_Mission &_mission, AP_AHRS &_ahrs, AP_SpdHgtControl *_SpdHgt_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,
adjusted_relative_altitude_cm_fn_t _adjusted_relative_altitude_cm_fn,
disarm_if_autoland_complete_fn_t _disarm_if_autoland_complete_fn,
update_flight_stage_fn_t _update_flight_stage_fn);
update_flight_stage_fn_t _update_flight_stage_fn) {
return AP_Landing{_mission, _ahrs, _SpdHgt_Controller, _nav_controller, _aparm,
_set_target_altitude_proportion_fn,
_constrain_target_altitude_location_fn,
_adjusted_altitude_cm_fn,
_adjusted_relative_altitude_cm_fn,
_disarm_if_autoland_complete_fn,
_update_flight_stage_fn};
}
constexpr AP_Landing(AP_Landing &&other) = default;
/* Do not allow copies */
AP_Landing(const AP_Landing &other) = delete;
AP_Landing &operator=(const AP_Landing&) = delete;
// NOTE: make sure to update is_type_valid()
@ -105,6 +117,13 @@ public:
float alt_offset;
private:
AP_Landing(AP_Mission &_mission, AP_AHRS &_ahrs, AP_SpdHgtControl *_SpdHgt_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,
adjusted_relative_altitude_cm_fn_t _adjusted_relative_altitude_cm_fn,
disarm_if_autoland_complete_fn_t _disarm_if_autoland_complete_fn,
update_flight_stage_fn_t _update_flight_stage_fn);
struct {
// denotes if a go-around has been commanded for landing