Browse Source

Plane: return success or failure of get home position

mission-4.1.18
DonLakeFlyer 9 years ago committed by Randy Mackay
parent
commit
7479bc5734
  1. 5
      ArduPlane/GCS_Mavlink.cpp

5
ArduPlane/GCS_Mavlink.cpp

@ -1305,7 +1305,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -1305,7 +1305,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
case MAV_CMD_GET_HOME_POSITION:
send_home(plane.ahrs.get_home());
if (plane.home_is_set != HOME_UNSET) {
send_home(plane.ahrs.get_home());
result = MAV_RESULT_ACCEPTED;
}
break;
case MAV_CMD_DO_SET_MODE:

Loading…
Cancel
Save