mirror of https://github.com/ArduPilot/ardupilot
Copter: fix tradheli landing detector bug
This commit is contained in:
parent
d66101d22f
commit
e333cb2717
|
@ -5,7 +5,7 @@
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
|
||||||
#ifndef HELI_DYNAMIC_FLIGHT_SPEED_MIN
|
#ifndef HELI_DYNAMIC_FLIGHT_SPEED_MIN
|
||||||
#define HELI_DYNAMIC_FLIGHT_SPEED_MIN 500 // we are in "dynamic flight" when the speed is over 5m/s for 2 seconds
|
#define HELI_DYNAMIC_FLIGHT_SPEED_MIN 250 // we are in "dynamic flight" when the speed is over 2.5m/s for 2 seconds
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// counter to control dynamic flight profile
|
// counter to control dynamic flight profile
|
||||||
|
|
|
@ -60,8 +60,11 @@ void Copter::update_land_detector()
|
||||||
} else {
|
} else {
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
// check that collective pitch is below mid collective (zero thrust) position
|
// check for both manual collective modes and modes that use altitude hold. For manual collective (called throttle
|
||||||
bool motor_at_lower_limit = (motors->get_below_mid_collective() && fabsf(ahrs.get_roll()) < M_PI/2.0f);
|
// because multi's use throttle), check that collective pitch is below mid collective (zero thrust) position. For modes
|
||||||
|
// that use altitude hold, check that the pilot is commanding a descent and collective is at min allowed for altitude hold modes.
|
||||||
|
bool motor_at_lower_limit = ((flightmode->has_manual_throttle() && motors->get_below_mid_collective() && fabsf(ahrs.get_roll()) < M_PI/2.0f)
|
||||||
|
|| (motors->limit.throttle_lower && pos_control->get_vel_desired_cms().z < 0.0f));
|
||||||
#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)
|
||||||
bool motor_at_lower_limit = motors->limit.throttle_lower && attitude_control->is_throttle_mix_min();
|
bool motor_at_lower_limit = motors->limit.throttle_lower && attitude_control->is_throttle_mix_min();
|
||||||
|
|
Loading…
Reference in New Issue