mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Copter: fixed apm1-hil build
This commit is contained in:
parent
f6d9bc5d7e
commit
6416a4d0e6
@ -174,8 +174,13 @@ static void land_nogps_run()
|
||||
// should be called at 100hz or higher
|
||||
static float get_throttle_land()
|
||||
{
|
||||
#if CONFIG_SONAR == ENABLED
|
||||
bool sonar_ok = sonar_enabled && sonar.healthy();
|
||||
#else
|
||||
bool sonar_ok = false;
|
||||
#endif
|
||||
// if we are above 10m and the sonar does not sense anything perform regular alt hold descent
|
||||
if (current_loc.alt >= LAND_START_ALT && !(sonar_enabled && sonar.healthy() && sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
if (current_loc.alt >= LAND_START_ALT && !(sonar_ok && sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
||||
return pos_control.get_speed_down();
|
||||
}else{
|
||||
return -abs(g.land_speed);
|
||||
|
@ -258,11 +258,13 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
||||
|
||||
case AUX_SWITCH_SONAR:
|
||||
// enable or disable the sonar
|
||||
#if CONFIG_SONAR == ENABLED
|
||||
if (ch_flag == AUX_SWITCH_HIGH) {
|
||||
sonar_enabled = true;
|
||||
}else{
|
||||
sonar_enabled = false;
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
|
||||
#if AC_FENCE == ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user