Copter: land detector requires desired climb rate be < -20cm/s

This commit is contained in:
Randy Mackay 2015-01-31 17:23:43 +09:00
parent ef4ca821c5
commit a067a5e623
2 changed files with 4 additions and 1 deletions

View File

@ -503,6 +503,9 @@
#ifndef LAND_DETECTOR_BARO_CLIMBRATE_MAX
# define LAND_DETECTOR_BARO_CLIMBRATE_MAX 150 // barometer climb rate must be between -150cm/s ~ +150cm/s
#endif
#ifndef LAND_DETECTOR_DESIRED_CLIMBRATE_MAX
# define LAND_DETECTOR_DESIRED_CLIMBRATE_MAX -20 // vehicle desired climb rate must be below -20cm/s
#endif
#ifndef LAND_DETECTOR_ROTATION_MAX
# define LAND_DETECTOR_ROTATION_MAX 0.50f // vehicle rotation must be below 0.5 rad/sec (=30deg/sec for) vehicle to consider itself landed
#endif

View File

@ -14,7 +14,7 @@ static bool land_complete_maybe()
static void update_land_detector()
{
bool climb_rate_low = (abs(climb_rate) < LAND_DETECTOR_CLIMBRATE_MAX) && (abs(baro_climbrate) < LAND_DETECTOR_BARO_CLIMBRATE_MAX);
bool target_climb_rate_low = !pos_control.is_active_z() || (pos_control.get_desired_velocity().z < LAND_SPEED);
bool target_climb_rate_low = !pos_control.is_active_z() || (pos_control.get_desired_velocity().z <= LAND_DETECTOR_DESIRED_CLIMBRATE_MAX);
bool motor_at_lower_limit = motors.limit.throttle_lower;
bool throttle_low = (FRAME_CONFIG == HELI_FRAME) || (motors.get_throttle_out() < get_non_takeoff_throttle());
bool not_rotating_fast = (ahrs.get_gyro().length() < LAND_DETECTOR_ROTATION_MAX);