mirror of https://github.com/ArduPilot/ardupilot
Plane: Added check for takeoff level-off timeout
When an airspeed sensor is not used, during a takeoff, the pitch angle is asymptotically driven to 0 as the takeoff altitude is approached. Some airplanes will then stop climbing and fail to reach altitude. To prevent an indefinite wait for the takeoff altitude to be reached, a dedicated level-off timeout has been introduced.
This commit is contained in:
parent
768b2eabc4
commit
9a5f81aa95
|
@ -453,7 +453,7 @@ private:
|
||||||
float throttle_lim_max;
|
float throttle_lim_max;
|
||||||
float throttle_lim_min;
|
float throttle_lim_min;
|
||||||
uint32_t throttle_max_timer_ms;
|
uint32_t throttle_max_timer_ms;
|
||||||
// Good candidate for keeping the initial time for TKOFF_THR_MAX_T.
|
uint32_t level_off_start_time_ms;
|
||||||
} takeoff_state;
|
} takeoff_state;
|
||||||
|
|
||||||
// ground steering controller state
|
// ground steering controller state
|
||||||
|
@ -1147,6 +1147,7 @@ private:
|
||||||
int16_t get_takeoff_pitch_min_cd(void);
|
int16_t get_takeoff_pitch_min_cd(void);
|
||||||
void landing_gear_update(void);
|
void landing_gear_update(void);
|
||||||
bool check_takeoff_timeout(void);
|
bool check_takeoff_timeout(void);
|
||||||
|
bool check_takeoff_timeout_level_off(void);
|
||||||
|
|
||||||
// avoidance_adsb.cpp
|
// avoidance_adsb.cpp
|
||||||
void avoidance_adsb_update(void);
|
void avoidance_adsb_update(void);
|
||||||
|
|
|
@ -589,7 +589,10 @@ bool Plane::verify_takeoff()
|
||||||
|
|
||||||
// see if we have reached takeoff altitude
|
// see if we have reached takeoff altitude
|
||||||
int32_t relative_alt_cm = adjusted_relative_altitude_cm();
|
int32_t relative_alt_cm = adjusted_relative_altitude_cm();
|
||||||
if (relative_alt_cm > auto_state.takeoff_altitude_rel_cm) {
|
if (
|
||||||
|
relative_alt_cm > auto_state.takeoff_altitude_rel_cm || // altitude reached
|
||||||
|
plane.check_takeoff_timeout_level_off() // pitch level-off maneuver has timed out
|
||||||
|
) {
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff complete at %.2fm",
|
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff complete at %.2fm",
|
||||||
(double)(relative_alt_cm*0.01f));
|
(double)(relative_alt_cm*0.01f));
|
||||||
steer_state.hold_course_cd = -1;
|
steer_state.hold_course_cd = -1;
|
||||||
|
|
|
@ -119,6 +119,7 @@ void ModeTakeoff::update()
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff to %.0fm for %.1fm heading %.1f deg",
|
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff to %.0fm for %.1fm heading %.1f deg",
|
||||||
alt, dist, direction);
|
alt, dist, direction);
|
||||||
plane.takeoff_state.start_time_ms = millis();
|
plane.takeoff_state.start_time_ms = millis();
|
||||||
|
plane.takeoff_state.level_off_start_time_ms = 0;
|
||||||
plane.takeoff_state.throttle_max_timer_ms = millis();
|
plane.takeoff_state.throttle_max_timer_ms = millis();
|
||||||
takeoff_mode_setup = true;
|
takeoff_mode_setup = true;
|
||||||
plane.steer_state.hold_course_cd = wrap_360_cd(direction*100); // Necessary to allow Plane::takeoff_calc_roll() to function.
|
plane.steer_state.hold_course_cd = wrap_360_cd(direction*100); // Necessary to allow Plane::takeoff_calc_roll() to function.
|
||||||
|
@ -157,6 +158,12 @@ void ModeTakeoff::update()
|
||||||
plane.set_flight_stage(AP_FixedWing::FlightStage::NORMAL);
|
plane.set_flight_stage(AP_FixedWing::FlightStage::NORMAL);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// If we have timed-out on the attempt to close the final few meters
|
||||||
|
// during pitch level-off, continue to NORMAL flight stage.
|
||||||
|
if (plane.check_takeoff_timeout_level_off()) {
|
||||||
|
plane.set_flight_stage(AP_FixedWing::FlightStage::NORMAL);
|
||||||
|
}
|
||||||
|
|
||||||
if (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF) {
|
if (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF) {
|
||||||
//below TKOFF_ALT
|
//below TKOFF_ALT
|
||||||
plane.takeoff_calc_roll();
|
plane.takeoff_calc_roll();
|
||||||
|
|
|
@ -121,6 +121,7 @@ bool Plane::auto_takeoff_check(void)
|
||||||
takeoff_state.launchTimerStarted = false;
|
takeoff_state.launchTimerStarted = false;
|
||||||
takeoff_state.last_tkoff_arm_time = 0;
|
takeoff_state.last_tkoff_arm_time = 0;
|
||||||
takeoff_state.start_time_ms = now;
|
takeoff_state.start_time_ms = now;
|
||||||
|
takeoff_state.level_off_start_time_ms = 0;
|
||||||
takeoff_state.throttle_max_timer_ms = now;
|
takeoff_state.throttle_max_timer_ms = now;
|
||||||
steer_state.locked_course_err = 0; // use current heading without any error offset
|
steer_state.locked_course_err = 0; // use current heading without any error offset
|
||||||
return true;
|
return true;
|
||||||
|
@ -316,6 +317,7 @@ int16_t Plane::get_takeoff_pitch_min_cd(void)
|
||||||
// make a note of that altitude to use it as a start height for scaling
|
// make a note of that altitude to use it as a start height for scaling
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff level-off starting at %dm", int(remaining_height_to_target_cm/100));
|
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff level-off starting at %dm", int(remaining_height_to_target_cm/100));
|
||||||
auto_state.height_below_takeoff_to_level_off_cm = remaining_height_to_target_cm;
|
auto_state.height_below_takeoff_to_level_off_cm = remaining_height_to_target_cm;
|
||||||
|
takeoff_state.level_off_start_time_ms = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -376,9 +378,8 @@ void Plane::landing_gear_update(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
check takeoff_timeout; checks time after the takeoff start time; returns true if timeout has occurred and disarms on timeout
|
check takeoff_timeout; checks time after the takeoff start time; returns true if timeout has occurred
|
||||||
*/
|
*/
|
||||||
|
|
||||||
bool Plane::check_takeoff_timeout(void)
|
bool Plane::check_takeoff_timeout(void)
|
||||||
{
|
{
|
||||||
if (takeoff_state.start_time_ms != 0 && g2.takeoff_timeout > 0) {
|
if (takeoff_state.start_time_ms != 0 && g2.takeoff_timeout > 0) {
|
||||||
|
@ -400,3 +401,17 @@ bool Plane::check_takeoff_timeout(void)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
check if the pitch level-off time has expired; returns true if timeout has occurred
|
||||||
|
*/
|
||||||
|
bool Plane::check_takeoff_timeout_level_off(void)
|
||||||
|
{
|
||||||
|
if (takeoff_state.level_off_start_time_ms > 0) {
|
||||||
|
// A takeoff is in progress.
|
||||||
|
uint32_t now = AP_HAL::millis();
|
||||||
|
if ((now - takeoff_state.level_off_start_time_ms) > (uint32_t)(1000U * g.takeoff_pitch_limit_reduction_sec)) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
Loading…
Reference in New Issue