mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
ArduCopter: fix handling of SET_HOME_POSITION
Location.altitude is stored in cm.
This commit is contained in:
parent
9398531811
commit
a310d3735e
@ -1976,7 +1976,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;
|
||||
if (copter.far_from_EKF_origin(new_home_loc)) {
|
||||
break;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user