Browse Source

GCS_MAVLink: fix home position unit

As per documentation the home position is in mm. Since location stores
it in cm, convert to mm before sending.
mission-4.1.18
Lucas De Marchi 9 years ago committed by Andrew Tridgell
parent
commit
0d9b9433da
  1. 4
      libraries/GCS_MAVLink/GCS_Common.cpp

4
libraries/GCS_MAVLink/GCS_Common.cpp

@ -1419,7 +1419,7 @@ void GCS_MAVLINK::send_home(const Location &home) const @@ -1419,7 +1419,7 @@ void GCS_MAVLINK::send_home(const Location &home) const
chan,
home.lat,
home.lng,
home.alt / 100,
home.alt * 10,
0.0f, 0.0f, 0.0f,
q,
0.0f, 0.0f, 0.0f);
@ -1437,7 +1437,7 @@ void GCS_MAVLINK::send_home_all(const Location &home) @@ -1437,7 +1437,7 @@ void GCS_MAVLINK::send_home_all(const Location &home)
chan,
home.lat,
home.lng,
home.alt / 100,
home.alt * 10,
0.0f, 0.0f, 0.0f,
q,
0.0f, 0.0f, 0.0f);

Loading…
Cancel
Save