|
|
|
@ -341,6 +341,7 @@ void Sub::update_altitude()
@@ -341,6 +341,7 @@ void Sub::update_altitude()
|
|
|
|
|
|
|
|
|
|
bool Sub::control_check_barometer() |
|
|
|
|
{ |
|
|
|
|
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL |
|
|
|
|
if (!ap.depth_sensor_present) { // can't hold depth without a depth sensor
|
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Depth sensor is not connected."); |
|
|
|
|
return false; |
|
|
|
@ -348,6 +349,7 @@ bool Sub::control_check_barometer()
@@ -348,6 +349,7 @@ bool Sub::control_check_barometer()
|
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Depth sensor error."); |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|