mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Landing: change namespace of MultiCopter and FixedWing params
this stops the libraries knowing anything about AP_Vehicle
This commit is contained in:
parent
5e21a95016
commit
28a9622a1e
@ -164,7 +164,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
|
|||||||
};
|
};
|
||||||
|
|
||||||
// constructor
|
// constructor
|
||||||
AP_Landing::AP_Landing(AP_Mission &_mission, AP_AHRS &_ahrs, AP_TECS *_tecs_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_FixedWing &_aparm,
|
||||||
set_target_altitude_proportion_fn_t _set_target_altitude_proportion_fn,
|
set_target_altitude_proportion_fn_t _set_target_altitude_proportion_fn,
|
||||||
constrain_target_altitude_location_fn_t _constrain_target_altitude_location_fn,
|
constrain_target_altitude_location_fn_t _constrain_target_altitude_location_fn,
|
||||||
adjusted_altitude_cm_fn_t _adjusted_altitude_cm_fn,
|
adjusted_altitude_cm_fn_t _adjusted_altitude_cm_fn,
|
||||||
@ -281,7 +281,7 @@ bool AP_Landing::verify_abort_landing(const Location &prev_WP_loc, Location &nex
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Landing::adjust_landing_slope_for_rangefinder_bump(AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state, Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc, const float wp_distance, int32_t &target_altitude_offset_cm)
|
void AP_Landing::adjust_landing_slope_for_rangefinder_bump(AP_FixedWing::Rangefinder_State &rangefinder_state, Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc, const float wp_distance, int32_t &target_altitude_offset_cm)
|
||||||
{
|
{
|
||||||
switch (type) {
|
switch (type) {
|
||||||
case TYPE_STANDARD_GLIDE_SLOPE:
|
case TYPE_STANDARD_GLIDE_SLOPE:
|
||||||
|
@ -36,7 +36,7 @@ public:
|
|||||||
FUNCTOR_TYPEDEF(disarm_if_autoland_complete_fn_t, void);
|
FUNCTOR_TYPEDEF(disarm_if_autoland_complete_fn_t, void);
|
||||||
FUNCTOR_TYPEDEF(update_flight_stage_fn_t, void);
|
FUNCTOR_TYPEDEF(update_flight_stage_fn_t, void);
|
||||||
|
|
||||||
AP_Landing(AP_Mission &_mission, AP_AHRS &_ahrs, AP_TECS *_tecs_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_FixedWing &_aparm,
|
||||||
set_target_altitude_proportion_fn_t _set_target_altitude_proportion_fn,
|
set_target_altitude_proportion_fn_t _set_target_altitude_proportion_fn,
|
||||||
constrain_target_altitude_location_fn_t _constrain_target_altitude_location_fn,
|
constrain_target_altitude_location_fn_t _constrain_target_altitude_location_fn,
|
||||||
adjusted_altitude_cm_fn_t _adjusted_altitude_cm_fn,
|
adjusted_altitude_cm_fn_t _adjusted_altitude_cm_fn,
|
||||||
@ -68,10 +68,10 @@ public:
|
|||||||
const int32_t auto_state_takeoff_altitude_rel_cm, bool &throttle_suppressed);
|
const int32_t auto_state_takeoff_altitude_rel_cm, bool &throttle_suppressed);
|
||||||
bool verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
bool verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
||||||
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);
|
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);
|
||||||
void adjust_landing_slope_for_rangefinder_bump(AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state, Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc, const float wp_distance, int32_t &target_altitude_offset_cm);
|
void adjust_landing_slope_for_rangefinder_bump(AP_FixedWing::Rangefinder_State &rangefinder_state, Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc, const float wp_distance, int32_t &target_altitude_offset_cm);
|
||||||
void setup_landing_glide_slope(const Location &prev_WP_loc, const Location &next_WP_loc, const Location ¤t_loc, int32_t &target_altitude_offset_cm);
|
void setup_landing_glide_slope(const Location &prev_WP_loc, const Location &next_WP_loc, const Location ¤t_loc, int32_t &target_altitude_offset_cm);
|
||||||
bool override_servos(void);
|
bool override_servos(void);
|
||||||
void check_if_need_to_abort(const AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state);
|
void check_if_need_to_abort(const AP_FixedWing::Rangefinder_State &rangefinder_state);
|
||||||
bool request_go_around(void);
|
bool request_go_around(void);
|
||||||
bool is_flaring(void) const;
|
bool is_flaring(void) const;
|
||||||
bool is_on_approach(void) const;
|
bool is_on_approach(void) const;
|
||||||
@ -137,7 +137,7 @@ private:
|
|||||||
AP_TECS *tecs_Controller;
|
AP_TECS *tecs_Controller;
|
||||||
AP_Navigation *nav_controller;
|
AP_Navigation *nav_controller;
|
||||||
|
|
||||||
AP_Vehicle::FixedWing &aparm;
|
AP_FixedWing &aparm;
|
||||||
|
|
||||||
set_target_altitude_proportion_fn_t set_target_altitude_proportion_fn;
|
set_target_altitude_proportion_fn_t set_target_altitude_proportion_fn;
|
||||||
constrain_target_altitude_location_fn_t constrain_target_altitude_location_fn;
|
constrain_target_altitude_location_fn_t constrain_target_altitude_location_fn;
|
||||||
@ -187,11 +187,11 @@ private:
|
|||||||
bool type_slope_verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
bool type_slope_verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
||||||
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);
|
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);
|
||||||
|
|
||||||
void type_slope_adjust_landing_slope_for_rangefinder_bump(AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state, Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc, const float wp_distance, int32_t &target_altitude_offset_cm);
|
void type_slope_adjust_landing_slope_for_rangefinder_bump(AP_FixedWing::Rangefinder_State &rangefinder_state, Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc, const float wp_distance, int32_t &target_altitude_offset_cm);
|
||||||
|
|
||||||
void type_slope_setup_landing_glide_slope(const Location &prev_WP_loc, const Location &next_WP_loc, const Location ¤t_loc, int32_t &target_altitude_offset_cm);
|
void type_slope_setup_landing_glide_slope(const Location &prev_WP_loc, const Location &next_WP_loc, const Location ¤t_loc, int32_t &target_altitude_offset_cm);
|
||||||
int32_t type_slope_get_target_airspeed_cm(void);
|
int32_t type_slope_get_target_airspeed_cm(void);
|
||||||
void type_slope_check_if_need_to_abort(const AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state);
|
void type_slope_check_if_need_to_abort(const AP_FixedWing::Rangefinder_State &rangefinder_state);
|
||||||
int32_t type_slope_constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd);
|
int32_t type_slope_constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd);
|
||||||
bool type_slope_request_go_around(void);
|
bool type_slope_request_go_around(void);
|
||||||
void type_slope_log(void) const;
|
void type_slope_log(void) const;
|
||||||
|
@ -181,7 +181,7 @@ bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &n
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Landing::type_slope_adjust_landing_slope_for_rangefinder_bump(AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state, Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc, const float wp_distance, int32_t &target_altitude_offset_cm)
|
void AP_Landing::type_slope_adjust_landing_slope_for_rangefinder_bump(AP_FixedWing::Rangefinder_State &rangefinder_state, Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc, const float wp_distance, int32_t &target_altitude_offset_cm)
|
||||||
{
|
{
|
||||||
// check the rangefinder correction for a large change. When found, recalculate the glide slope. This is done by
|
// check the rangefinder correction for a large change. When found, recalculate the glide slope. This is done by
|
||||||
// determining the slope from your current location to the land point then following that back up to the approach
|
// determining the slope from your current location to the land point then following that back up to the approach
|
||||||
|
Loading…
Reference in New Issue
Block a user