mirror of https://github.com/ArduPilot/ardupilot
Rover: tidy WATER_DEPTH send checks
This commit is contained in:
parent
07edfdd323
commit
73710d888d
|
@ -199,9 +199,14 @@ void GCS_MAVLINK_Rover::send_water_depth() const
|
|||
|
||||
RangeFinder *rangefinder = RangeFinder::get_singleton();
|
||||
|
||||
if (rangefinder == nullptr || !rangefinder->has_orientation(ROTATION_PITCH_270)){
|
||||
if (rangefinder == nullptr) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// depth can only be measured by a downward-facing rangefinder:
|
||||
if (!rangefinder->has_orientation(ROTATION_PITCH_270)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// get position
|
||||
const AP_AHRS &ahrs = AP::ahrs();
|
||||
|
|
Loading…
Reference in New Issue