mirror of https://github.com/ArduPilot/ardupilot
Copter: ensure force flying with heli inverted flag
This commit is contained in:
parent
a07b514ee8
commit
0de2d6d482
|
@ -830,7 +830,8 @@ private:
|
||||||
void set_land_complete(bool b);
|
void set_land_complete(bool b);
|
||||||
void set_land_complete_maybe(bool b);
|
void set_land_complete_maybe(bool b);
|
||||||
void update_throttle_mix();
|
void update_throttle_mix();
|
||||||
|
bool get_force_flying() const;
|
||||||
|
|
||||||
#if AP_LANDINGGEAR_ENABLED
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
// landing_gear.cpp
|
// landing_gear.cpp
|
||||||
void landinggear_update();
|
void landinggear_update();
|
||||||
|
|
|
@ -36,7 +36,7 @@ void Copter::crash_check()
|
||||||
}
|
}
|
||||||
|
|
||||||
// exit immediately if in force flying
|
// exit immediately if in force flying
|
||||||
if (force_flying && !flightmode->is_landing()) {
|
if (get_force_flying() && !flightmode->is_landing()) {
|
||||||
crash_counter = 0;
|
crash_counter = 0;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
|
@ -78,7 +78,7 @@ void Copter::update_land_detector()
|
||||||
#if MODE_AUTOROTATE_ENABLED == ENABLED
|
#if MODE_AUTOROTATE_ENABLED == ENABLED
|
||||||
|| (flightmode->mode_number() == Mode::Number::AUTOROTATE && motors->get_below_land_min_coll())
|
|| (flightmode->mode_number() == Mode::Number::AUTOROTATE && motors->get_below_land_min_coll())
|
||||||
#endif
|
#endif
|
||||||
|| ((!force_flying || landing) && motors->limit.throttle_lower && pos_control->get_vel_desired_cms().z < 0.0f);
|
|| ((!get_force_flying() || landing) && motors->limit.throttle_lower && pos_control->get_vel_desired_cms().z < 0.0f);
|
||||||
bool throttle_mix_at_min = true;
|
bool throttle_mix_at_min = true;
|
||||||
#else
|
#else
|
||||||
// check that the average throttle output is near minimum (less than 12.5% hover throttle)
|
// check that the average throttle output is near minimum (less than 12.5% hover throttle)
|
||||||
|
@ -251,7 +251,7 @@ void Copter::update_throttle_mix()
|
||||||
// check if landing
|
// check if landing
|
||||||
const bool landing = flightmode->is_landing();
|
const bool landing = flightmode->is_landing();
|
||||||
|
|
||||||
if (((large_angle_request || force_flying) && !landing) || large_angle_error || accel_moving || descent_not_demanded) {
|
if (((large_angle_request || get_force_flying()) && !landing) || large_angle_error || accel_moving || descent_not_demanded) {
|
||||||
attitude_control->set_throttle_mix_max(pos_control->get_vel_z_control_ratio());
|
attitude_control->set_throttle_mix_max(pos_control->get_vel_z_control_ratio());
|
||||||
} else {
|
} else {
|
||||||
attitude_control->set_throttle_mix_min();
|
attitude_control->set_throttle_mix_min();
|
||||||
|
@ -259,3 +259,14 @@ void Copter::update_throttle_mix()
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// helper function for force flying flag
|
||||||
|
bool Copter::get_force_flying() const
|
||||||
|
{
|
||||||
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
if (attitude_control->get_inverted_flight()) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
return force_flying;
|
||||||
|
}
|
Loading…
Reference in New Issue