Plane: move MAV_CMD_START_RX_PAIR handling to base class

This commit is contained in:
Peter Barker 2017-07-17 09:49:41 +10:00 committed by Francisco Ferreira
parent ecda9116ba
commit 2b6752e0b4

View File

@ -1088,10 +1088,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
}
break;
case MAV_CMD_START_RX_PAIR:
result = handle_rc_bind(packet);
break;
case MAV_CMD_NAV_LOITER_UNLIM:
plane.set_mode(LOITER, MODE_REASON_GCS_COMMAND);
result = MAV_RESULT_ACCEPTED;