mirror of https://github.com/ArduPilot/ardupilot
Copter: landing detector checks baro climb rate
Barometer climb rate must be -150cm/s ~ +150cm/s This threshold is generous because we already use the inertial navigation climb rate so this is just to catch cases where inertial nav is very incorrect in it's climbrate estimates
This commit is contained in:
parent
e6c6fe095f
commit
f6ff1742d5
|
@ -581,8 +581,8 @@ static int16_t climb_rate;
|
||||||
static int16_t sonar_alt;
|
static int16_t sonar_alt;
|
||||||
static uint8_t sonar_alt_health; // true if we can trust the altitude from the sonar
|
static uint8_t sonar_alt_health; // true if we can trust the altitude from the sonar
|
||||||
static float target_sonar_alt; // desired altitude in cm above the ground
|
static float target_sonar_alt; // desired altitude in cm above the ground
|
||||||
// The altitude as reported by Baro in cm - Values can be quite high
|
static int32_t baro_alt; // barometer altitude in cm above home
|
||||||
static int32_t baro_alt;
|
static float baro_climbrate; // barometer climbrate in cm/s
|
||||||
|
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -1373,7 +1373,7 @@ static void read_AHRS(void)
|
||||||
static void update_altitude()
|
static void update_altitude()
|
||||||
{
|
{
|
||||||
// read in baro altitude
|
// read in baro altitude
|
||||||
baro_alt = read_barometer();
|
read_barometer();
|
||||||
|
|
||||||
// read in sonar altitude
|
// read in sonar altitude
|
||||||
sonar_alt = read_sonar();
|
sonar_alt = read_sonar();
|
||||||
|
|
|
@ -498,6 +498,9 @@
|
||||||
#ifndef LAND_DETECTOR_CLIMBRATE_MAX
|
#ifndef LAND_DETECTOR_CLIMBRATE_MAX
|
||||||
# define LAND_DETECTOR_CLIMBRATE_MAX 30 // vehicle climb rate must be between -30 and +30 cm/s
|
# define LAND_DETECTOR_CLIMBRATE_MAX 30 // vehicle climb rate must be between -30 and +30 cm/s
|
||||||
#endif
|
#endif
|
||||||
|
#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_ROTATION_MAX
|
#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
|
# 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
|
#endif
|
||||||
|
|
|
@ -203,7 +203,9 @@ static bool land_complete_maybe()
|
||||||
static void update_land_detector()
|
static void update_land_detector()
|
||||||
{
|
{
|
||||||
// detect whether we have landed by watching for low climb rate, motors hitting their lower limit, overall low throttle and low rotation rate
|
// detect whether we have landed by watching for low climb rate, motors hitting their lower limit, overall low throttle and low rotation rate
|
||||||
if ((abs(climb_rate) < LAND_DETECTOR_CLIMBRATE_MAX) && motors.limit.throttle_lower &&
|
if ((abs(climb_rate) < LAND_DETECTOR_CLIMBRATE_MAX) &&
|
||||||
|
(abs(baro_climbrate) < LAND_DETECTOR_BARO_CLIMBRATE_MAX) &&
|
||||||
|
motors.limit.throttle_lower &&
|
||||||
#if FRAME_CONFIG != HELI_FRAME
|
#if FRAME_CONFIG != HELI_FRAME
|
||||||
(motors.get_throttle_out() < get_non_takeoff_throttle()) &&
|
(motors.get_throttle_out() < get_non_takeoff_throttle()) &&
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -19,13 +19,14 @@ static void init_barometer(bool full_calibration)
|
||||||
}
|
}
|
||||||
|
|
||||||
// return barometric altitude in centimeters
|
// return barometric altitude in centimeters
|
||||||
static int32_t read_barometer(void)
|
static void read_barometer(void)
|
||||||
{
|
{
|
||||||
barometer.read();
|
barometer.read();
|
||||||
if (should_log(MASK_LOG_IMU)) {
|
if (should_log(MASK_LOG_IMU)) {
|
||||||
Log_Write_Baro();
|
Log_Write_Baro();
|
||||||
}
|
}
|
||||||
int32_t balt = barometer.get_altitude() * 100.0f;
|
baro_alt = barometer.get_altitude() * 100.0f;
|
||||||
|
baro_climbrate = barometer.get_climb_rate() * 100.0f;
|
||||||
|
|
||||||
// run glitch protection and update AP_Notify if home has been initialised
|
// run glitch protection and update AP_Notify if home has been initialised
|
||||||
baro_glitch.check_alt();
|
baro_glitch.check_alt();
|
||||||
|
@ -38,9 +39,6 @@ static int32_t read_barometer(void)
|
||||||
}
|
}
|
||||||
AP_Notify::flags.baro_glitching = report_baro_glitch;
|
AP_Notify::flags.baro_glitching = report_baro_glitch;
|
||||||
}
|
}
|
||||||
|
|
||||||
// return altitude
|
|
||||||
return balt;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// return sonar altitude in centimeters
|
// return sonar altitude in centimeters
|
||||||
|
|
|
@ -58,13 +58,13 @@ test_baro(uint8_t argc, const Menu::arg *argv)
|
||||||
|
|
||||||
while(1) {
|
while(1) {
|
||||||
delay(100);
|
delay(100);
|
||||||
alt = read_barometer();
|
read_barometer();
|
||||||
|
|
||||||
if (!barometer.healthy()) {
|
if (!barometer.healthy()) {
|
||||||
cliSerial->println_P(PSTR("not healthy"));
|
cliSerial->println_P(PSTR("not healthy"));
|
||||||
} else {
|
} else {
|
||||||
cliSerial->printf_P(PSTR("Alt: %0.2fm, Raw: %f Temperature: %.1f\n"),
|
cliSerial->printf_P(PSTR("Alt: %0.2fm, Raw: %f Temperature: %.1f\n"),
|
||||||
alt / 100.0,
|
baro_alt / 100.0,
|
||||||
barometer.get_pressure(),
|
barometer.get_pressure(),
|
||||||
barometer.get_temperature());
|
barometer.get_temperature());
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue