mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Copter: return success or failure of get home position
This commit is contained in:
parent
78e9b0a4e3
commit
c8cc83505b
@ -1387,7 +1387,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_GET_HOME_POSITION:
|
case MAV_CMD_GET_HOME_POSITION:
|
||||||
send_home(copter.ahrs.get_home());
|
if (copter.ap.home_state != HOME_UNSET) {
|
||||||
|
send_home(copter.ahrs.get_home());
|
||||||
|
result = MAV_RESULT_ACCEPTED;
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_CMD_DO_SET_SERVO:
|
case MAV_CMD_DO_SET_SERVO:
|
||||||
|
Loading…
Reference in New Issue
Block a user