mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Terrain: fixed cm conversion error
This commit is contained in:
parent
18974363d5
commit
5e2077185b
@ -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)
|
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) {
|
if (!loc.flags.relative_alt) {
|
||||||
// loc.alt has home altitude added, remove it
|
// loc.alt has home altitude added, remove it
|
||||||
relative_home_altitude -= ahrs.get_home().alt*0.01f;
|
relative_home_altitude -= ahrs.get_home().alt*0.01f;
|
||||||
|
Loading…
Reference in New Issue
Block a user