mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Copter: provide terrain height to rangefinder
used for power saving
This commit is contained in:
parent
422d0f05bd
commit
7c975808f8
@ -1149,6 +1149,15 @@ static void one_hz_loop()
|
||||
|
||||
#if AP_TERRAIN_AVAILABLE
|
||||
terrain.update();
|
||||
|
||||
// tell the rangefinder our height, so it can go into power saving
|
||||
// mode if available
|
||||
#if CONFIG_SONAR == ENABLED
|
||||
float height;
|
||||
if (terrain.height_above_terrain(height, true)) {
|
||||
sonar.set_estimated_terrain_height(height);
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if AC_FENCE == ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user