Browse Source

Copter: provide terrain height to rangefinder

used for power saving
mission-4.1.18
Andrew Tridgell 10 years ago
parent
commit
7c975808f8
  1. 9
      ArduCopter/ArduCopter.pde

9
ArduCopter/ArduCopter.pde

@ -1149,6 +1149,15 @@ static void one_hz_loop() @@ -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…
Cancel
Save