Browse Source

Sub: Fix handling of SET_HOME_POSITION

mission-4.1.18
Rustom Jehangir 9 years ago committed by Andrew Tridgell
parent
commit
3c6b6ba8e9
  1. 2
      ArduSub/GCS_Mavlink.cpp

2
ArduSub/GCS_Mavlink.cpp

@ -1981,7 +1981,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -1981,7 +1981,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 (sub.far_from_EKF_origin(new_home_loc)) {
break;
}

Loading…
Cancel
Save