mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 22:18:28 -04:00
AP_Landing_Slope: Log height used for flare timing.
This commit is contained in:
parent
9f77d5ac9d
commit
27f0320452
@ -131,6 +131,8 @@ private:
|
|||||||
// calculated approach slope during auto-landing: ((prev_WP_loc.alt - next_WP_loc.alt)*0.01f - flare_sec * sink_rate) / prev_WP_loc.get_distance(next_WP_loc)
|
// calculated approach slope during auto-landing: ((prev_WP_loc.alt - next_WP_loc.alt)*0.01f - flare_sec * sink_rate) / prev_WP_loc.get_distance(next_WP_loc)
|
||||||
float slope;
|
float slope;
|
||||||
|
|
||||||
|
float height_flare_log;
|
||||||
|
|
||||||
AP_Mission &mission;
|
AP_Mission &mission;
|
||||||
AP_AHRS &ahrs;
|
AP_AHRS &ahrs;
|
||||||
AP_SpdHgtControl *SpdHgt_Controller;
|
AP_SpdHgtControl *SpdHgt_Controller;
|
||||||
|
@ -89,6 +89,8 @@ bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &n
|
|||||||
const bool below_flare_sec = (flare_sec > 0 && height <= sink_rate * flare_sec);
|
const bool below_flare_sec = (flare_sec > 0 && height <= sink_rate * flare_sec);
|
||||||
const bool probably_crashed = (aparm.crash_detection_enable && fabsf(sink_rate) < 0.2f && !is_flying);
|
const bool probably_crashed = (aparm.crash_detection_enable && fabsf(sink_rate) < 0.2f && !is_flying);
|
||||||
|
|
||||||
|
height_flare_log = height;
|
||||||
|
|
||||||
const AP_GPS &gps = AP::gps();
|
const AP_GPS &gps = AP::gps();
|
||||||
|
|
||||||
if ((on_approach_stage && below_flare_alt) ||
|
if ((on_approach_stage && below_flare_alt) ||
|
||||||
@ -405,14 +407,16 @@ void AP_Landing::type_slope_log(void) const
|
|||||||
// @Field: slope: Slope to landing point
|
// @Field: slope: Slope to landing point
|
||||||
// @Field: slopeInit: Initial slope to landing point
|
// @Field: slopeInit: Initial slope to landing point
|
||||||
// @Field: altO: Rangefinder correction
|
// @Field: altO: Rangefinder correction
|
||||||
AP::logger().Write("LAND", "TimeUS,stage,f1,f2,slope,slopeInit,altO", "QBBBfff",
|
// @Field: fh: Height for flare timing.
|
||||||
|
AP::logger().Write("LAND", "TimeUS,stage,f1,f2,slope,slopeInit,altO,fh", "QBBBffff",
|
||||||
AP_HAL::micros64(),
|
AP_HAL::micros64(),
|
||||||
type_slope_stage,
|
type_slope_stage,
|
||||||
flags,
|
flags,
|
||||||
type_slope_flags,
|
type_slope_flags,
|
||||||
(double)slope,
|
(double)slope,
|
||||||
(double)initial_slope,
|
(double)initial_slope,
|
||||||
(double)alt_offset);
|
(double)alt_offset,
|
||||||
|
(double)height_flare_log);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_Landing::type_slope_is_throttle_suppressed(void) const
|
bool AP_Landing::type_slope_is_throttle_suppressed(void) const
|
||||||
|
Loading…
Reference in New Issue
Block a user