mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 04:28:30 -04:00
AP_Landing: Add a servo override interface and PID logging interface
This commit is contained in:
parent
ed359a5833
commit
8b20577b74
@ -288,6 +288,29 @@ bool AP_Landing::is_expecting_impact(void) const
|
||||
}
|
||||
}
|
||||
|
||||
// returns true when the landing library has overriden any servos
|
||||
bool AP_Landing::override_servos(void) {
|
||||
if (!flags.in_progress) {
|
||||
return false;
|
||||
}
|
||||
|
||||
switch (type) {
|
||||
case TYPE_STANDARD_GLIDE_SLOPE:
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// returns a PID_Info object if there is one available for the selected landing
|
||||
// type, otherwise returns a nullptr, indicating no data to be logged/sent
|
||||
const DataFlash_Class::PID_Info* AP_Landing::get_pid_info(void) const
|
||||
{
|
||||
switch (type) {
|
||||
case TYPE_STANDARD_GLIDE_SLOPE:
|
||||
default:
|
||||
return nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
a special glide slope calculation for the landing approach
|
||||
|
@ -74,6 +74,7 @@ public:
|
||||
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 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);
|
||||
void check_if_need_to_abort(const AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state);
|
||||
bool request_go_around(void);
|
||||
bool is_flaring(void) const;
|
||||
@ -104,6 +105,7 @@ public:
|
||||
void set_initial_slope(void) { initial_slope = slope; }
|
||||
bool is_expecting_impact(void) const;
|
||||
void log(void) const;
|
||||
const DataFlash_Class::PID_Info * get_pid_info(void) const;
|
||||
|
||||
// landing altitude offset (meters)
|
||||
float alt_offset;
|
||||
|
Loading…
Reference in New Issue
Block a user