Rover: Return RESULT_FAILED for GET_CMD_HOME if home is unset
This commit is contained in:
parent
bec4bfa2ba
commit
f1f8233220
@ -1105,6 +1105,8 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
||||
if (rover.home_is_set != HOME_UNSET) {
|
||||
send_home(rover.ahrs.get_home());
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
} else {
|
||||
result = MAV_RESULT_FAILED;
|
||||
}
|
||||
break;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user