Rover: return success or failure of get home position
This commit is contained in:
parent
c8cc83505b
commit
0950c97866
@ -1095,7 +1095,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
|
||||
case MAV_CMD_GET_HOME_POSITION:
|
||||
send_home(rover.ahrs.get_home());
|
||||
if (rover.home_is_set != HOME_UNSET) {
|
||||
send_home(rover.ahrs.get_home());
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
break;
|
||||
|
||||
case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: {
|
||||
|
Loading…
Reference in New Issue
Block a user