Browse Source

Plane: return MAV_RESULT_ACCEPTED for setting home to current location

master
Peter Barker 7 years ago committed by Andrew Tridgell
parent
commit
18c4823427
  1. 2
      ArduPlane/GCS_Mavlink.cpp

2
ArduPlane/GCS_Mavlink.cpp

@ -777,6 +777,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg) @@ -777,6 +777,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
result = MAV_RESULT_FAILED; // assume failure
if (is_equal(packet.param1, 1.0f)) {
plane.set_home_persistently(AP::gps().location());
result = MAV_RESULT_ACCEPTED;
} else {
// ensure param1 is zero
if (!is_zero(packet.param1)) {
@ -1071,6 +1072,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg) @@ -1071,6 +1072,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
result = MAV_RESULT_FAILED; // assume failure
if (is_equal(packet.param1,1.0f)) {
plane.set_home_persistently(AP::gps().location());
result = MAV_RESULT_ACCEPTED;
} else {
// ensure param1 is zero
if (!is_zero(packet.param1)) {

Loading…
Cancel
Save