mirror of https://github.com/ArduPilot/ardupilot
Copter: keep manual throttle mix at zero throttle when airmode is on
allow landing detection in airmode increase landing detection timeout in airmode.
This commit is contained in:
parent
f7d21b63a7
commit
877f98e547
|
@ -417,6 +417,9 @@
|
|||
#ifndef LAND_DETECTOR_TRIGGER_SEC
|
||||
# define LAND_DETECTOR_TRIGGER_SEC 1.0f // number of seconds to detect a landing
|
||||
#endif
|
||||
#ifndef LAND_AIRMODE_DETECTOR_TRIGGER_SEC
|
||||
# define LAND_AIRMODE_DETECTOR_TRIGGER_SEC 3.0f // number of seconds to detect a landing in air mode
|
||||
#endif
|
||||
#ifndef LAND_DETECTOR_MAYBE_TRIGGER_SEC
|
||||
# define LAND_DETECTOR_MAYBE_TRIGGER_SEC 0.2f // number of seconds that means we might be landed (used to reset horizontal position targets to prevent tipping over)
|
||||
#endif
|
||||
|
|
|
@ -60,6 +60,7 @@ void Copter::update_land_detector()
|
|||
land_detector_count = 0;
|
||||
} else {
|
||||
|
||||
float land_trigger_sec = LAND_DETECTOR_TRIGGER_SEC;
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// check for both manual collective modes and modes that use altitude hold. For manual collective (called throttle
|
||||
// because multi's use throttle), check that collective pitch is below land min collective position or throttle stick is zero.
|
||||
|
@ -70,9 +71,17 @@ void Copter::update_land_detector()
|
|||
const bool landing = flightmode->is_landing();
|
||||
bool motor_at_lower_limit = (flightmode->has_manual_throttle() && (motors->get_below_land_min_coll() || heli_flags.coll_stk_low) && fabsf(ahrs.get_roll()) < M_PI/2.0f)
|
||||
|| ((!force_flying || landing) && motors->limit.throttle_lower && pos_control->get_vel_desired_cms().z < 0.0f);
|
||||
bool throttle_mix_at_min = true;
|
||||
#else
|
||||
// check that the average throttle output is near minimum (less than 12.5% hover throttle)
|
||||
bool motor_at_lower_limit = motors->limit.throttle_lower && attitude_control->is_throttle_mix_min();
|
||||
bool motor_at_lower_limit = motors->limit.throttle_lower;
|
||||
bool throttle_mix_at_min = attitude_control->is_throttle_mix_min();
|
||||
// set throttle_mix_at_min to true because throttle is never at mix min in airmode
|
||||
// increase land_trigger_sec when using airmode
|
||||
if (flightmode->has_manual_throttle() && air_mode == AirMode::AIRMODE_ENABLED) {
|
||||
land_trigger_sec = LAND_AIRMODE_DETECTOR_TRIGGER_SEC;
|
||||
throttle_mix_at_min = true;
|
||||
}
|
||||
#endif
|
||||
|
||||
uint8_t land_detector_scalar = 1;
|
||||
|
@ -99,9 +108,9 @@ void Copter::update_land_detector()
|
|||
const bool WoW_check = true;
|
||||
#endif
|
||||
|
||||
if (motor_at_lower_limit && accel_stationary && descent_rate_low && rangefinder_check && WoW_check) {
|
||||
if (motor_at_lower_limit && throttle_mix_at_min && accel_stationary && descent_rate_low && rangefinder_check && WoW_check) {
|
||||
// landed criteria met - increment the counter and check if we've triggered
|
||||
if( land_detector_count < ((float)LAND_DETECTOR_TRIGGER_SEC)*scheduler.get_loop_rate_hz()) {
|
||||
if( land_detector_count < land_trigger_sec*scheduler.get_loop_rate_hz()) {
|
||||
land_detector_count++;
|
||||
} else {
|
||||
set_land_complete(true);
|
||||
|
@ -174,7 +183,7 @@ void Copter::update_throttle_mix()
|
|||
|
||||
if (flightmode->has_manual_throttle()) {
|
||||
// manual throttle
|
||||
if (channel_throttle->get_control_in() <= 0 || air_mode == AirMode::AIRMODE_DISABLED) {
|
||||
if (channel_throttle->get_control_in() <= 0 && air_mode != AirMode::AIRMODE_ENABLED) {
|
||||
attitude_control->set_throttle_mix_min();
|
||||
} else {
|
||||
attitude_control->set_throttle_mix_man();
|
||||
|
|
Loading…
Reference in New Issue