AP_Landing: fixed compiler warnings

- init variable out of order, callbacks were declared first
This commit is contained in:
Tom Pittenger 2016-12-05 16:15:20 -08:00
parent 79a9e8dfad
commit 725a9c40a6
1 changed files with 16 additions and 21 deletions

View File

@ -28,30 +28,12 @@ class AP_Landing
{
public:
enum Landing_Type {
TYPE_STANDARD_GLIDE_SLOPE = 0,
// TODO: TYPE_DEEPSTALL,
// TODO: TYPE_PARACHUTE,
// TODO: TYPE_HELICAL,
};
FUNCTOR_TYPEDEF(set_target_altitude_proportion_fn_t, void, const Location&, float);
set_target_altitude_proportion_fn_t set_target_altitude_proportion_fn;
FUNCTOR_TYPEDEF(constrain_target_altitude_location_fn_t, void, const Location&, const Location&);
constrain_target_altitude_location_fn_t constrain_target_altitude_location_fn;
FUNCTOR_TYPEDEF(adjusted_altitude_cm_fn_t, int32_t);
adjusted_altitude_cm_fn_t adjusted_altitude_cm_fn;
FUNCTOR_TYPEDEF(adjusted_relative_altitude_cm_fn_t, int32_t);
adjusted_relative_altitude_cm_fn_t adjusted_relative_altitude_cm_fn;
FUNCTOR_TYPEDEF(disarm_if_autoland_complete_fn_t, void);
disarm_if_autoland_complete_fn_t disarm_if_autoland_complete_fn;
FUNCTOR_TYPEDEF(update_flight_stage_fn_t, void);
update_flight_stage_fn_t update_flight_stage_fn;
// constructor
AP_Landing(AP_Mission &_mission, AP_AHRS &_ahrs, AP_SpdHgtControl *_SpdHgt_Controller, AP_Navigation *_nav_controller, AP_Vehicle::FixedWing &_aparm,
@ -71,10 +53,18 @@ public:
,adjusted_altitude_cm_fn(_adjusted_altitude_cm_fn)
,adjusted_relative_altitude_cm_fn(_adjusted_relative_altitude_cm_fn)
,disarm_if_autoland_complete_fn(_disarm_if_autoland_complete_fn)
,update_flight_stage_fn(_update_flight_stage_fn) {
,update_flight_stage_fn(_update_flight_stage_fn)
{
AP_Param::setup_object_defaults(this, var_info);
}
enum Landing_Type {
TYPE_STANDARD_GLIDE_SLOPE = 0,
// TODO: TYPE_DEEPSTALL,
// TODO: TYPE_PARACHUTE,
// TODO: TYPE_HELICAL,
};
bool restart_landing_sequence();
bool verify_land(const AP_SpdHgtControl::FlightStage flight_stage, const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc,
const int32_t auto_state_takeoff_altitude_rel_cm, const float height, const float sink_rate, const float wp_proportion, const uint32_t last_flying_ms, const bool is_armed, const bool is_flying, const bool rangefinder_state_in_range, bool &throttle_suppressed);
@ -137,6 +127,13 @@ private:
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;
AP_Int16 pitch_cd;
AP_Float flare_alt;
AP_Float flare_sec;
@ -152,8 +149,6 @@ private:
AP_Int8 throttle_slewrate;
AP_Int8 type;
// Land Type STANDARD GLIDE SLOPE
bool type_slope_verify_land(const AP_SpdHgtControl::FlightStage flight_stage, const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc,
const int32_t auto_state_takeoff_altitude_rel_cm, const float height, const float sink_rate, const float wp_proportion, const uint32_t last_flying_ms, const bool is_armed, const bool is_flying, const bool rangefinder_state_in_range, bool &throttle_suppressed);