Browse Source

AP_Terrain: fixed cm conversion error

master
Andrew Tridgell 11 years ago
parent
commit
5e2077185b
  1. 2
      libraries/AP_Terrain/AP_Terrain.cpp

2
libraries/AP_Terrain/AP_Terrain.cpp

@ -189,7 +189,7 @@ bool AP_Terrain::height_above_terrain(const Location &loc, float relative_home_a @@ -189,7 +189,7 @@ bool AP_Terrain::height_above_terrain(const Location &loc, float relative_home_a
*/
bool AP_Terrain::height_above_terrain(const Location &loc, float &terrain_altitude)
{
float relative_home_altitude = loc.alt;
float relative_home_altitude = loc.alt*0.01f;
if (!loc.flags.relative_alt) {
// loc.alt has home altitude added, remove it
relative_home_altitude -= ahrs.get_home().alt*0.01f;

Loading…
Cancel
Save