mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 06:58:27 -04:00
Rover: only send WATER_DEPTH for boat frames
This commit is contained in:
parent
9f2253a109
commit
07edfdd323
@ -192,6 +192,11 @@ void GCS_MAVLINK_Rover::send_water_depth() const
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// only send for boats:
|
||||||
|
if (!rover.is_boat()) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
RangeFinder *rangefinder = RangeFinder::get_singleton();
|
RangeFinder *rangefinder = RangeFinder::get_singleton();
|
||||||
|
|
||||||
if (rangefinder == nullptr || !rangefinder->has_orientation(ROTATION_PITCH_270)){
|
if (rangefinder == nullptr || !rangefinder->has_orientation(ROTATION_PITCH_270)){
|
||||||
|
Loading…
Reference in New Issue
Block a user