Browse Source

ArduPlane: fix handling of SET_HOME_POSITION

Location.altitude is stored in cm.
mission-4.1.18
Lucas De Marchi 9 years ago committed by Andrew Tridgell
parent
commit
0095f6168e
  1. 2
      ArduPlane/GCS_Mavlink.cpp

2
ArduPlane/GCS_Mavlink.cpp

@ -2014,7 +2014,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -2014,7 +2014,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
Location new_home_loc {};
new_home_loc.lat = packet.latitude;
new_home_loc.lng = packet.longitude;
new_home_loc.alt = packet.altitude * 100;
new_home_loc.alt = packet.altitude / 10;
plane.ahrs.set_home(new_home_loc);
plane.home_is_set = HOME_SET_NOT_LOCKED;
plane.Log_Write_Home_And_Origin();

Loading…
Cancel
Save