AP_Terrain: fixed cm conversion error

This commit is contained in:
Andrew Tridgell 2014-07-24 17:52:57 +10:00
parent 18974363d5
commit 5e2077185b

View File

@ -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;