private void updateFlightModeButtons() {
    resetFlightModeButtons();

    final Drone drone = getDrone();
    final State droneState = drone.getAttribute(AttributeType.STATE);
    final VehicleMode flightMode = droneState.getVehicleMode();
    if (flightMode != null) {
      switch (flightMode) {
        case PLANE_AUTO:
          autoBtn.setActivated(true);
          break;

        case PLANE_GUIDED:
          final GuidedState guidedState = drone.getAttribute(AttributeType.GUIDED_STATE);
          final FollowState followState = drone.getAttribute(AttributeType.FOLLOW_STATE);
          if (guidedState.isInitialized() && !followState.isEnabled()) {
            pauseBtn.setActivated(true);
          }
          break;

        case PLANE_RTL:
          homeBtn.setActivated(true);
          break;
      }
    }
  }
 @Override
 public boolean isSlidingUpPanelEnabled(Drone drone) {
   final State droneState = drone.getAttribute(AttributeType.STATE);
   return droneState.isConnected() && droneState.isArmed() && droneState.isFlying();
 }
  @Override
  public void onClick(View v) {
    final Drone drone = getDrone();
    HitBuilders.EventBuilder eventBuilder =
        new HitBuilders.EventBuilder().setCategory(GAUtils.Category.FLIGHT);

    switch (v.getId()) {
      case R.id.mc_connectBtn:
        ((SuperUI) getActivity()).toggleDroneConnection();
        break;

      case R.id.mc_armBtn:
        getArmingConfirmation();
        eventBuilder.setAction(ACTION_FLIGHT_ACTION_BUTTON).setLabel("Arm");
        break;

      case R.id.mc_disarmBtn:
        getDrone().arm(false);
        eventBuilder.setAction(ACTION_FLIGHT_ACTION_BUTTON).setLabel("Disarm");
        break;

      case R.id.mc_homeBtn:
        drone.changeVehicleMode(VehicleMode.PLANE_RTL);
        eventBuilder
            .setAction(ACTION_FLIGHT_ACTION_BUTTON)
            .setLabel(VehicleMode.PLANE_RTL.getLabel());
        break;

      case R.id.mc_pause:
        {
          final FollowState followState = drone.getAttribute(AttributeType.FOLLOW_STATE);
          if (followState.isEnabled()) {
            drone.disableFollowMe();
          }

          drone.pauseAtCurrentLocation();
          eventBuilder.setAction(ACTION_FLIGHT_ACTION_BUTTON).setLabel("Pause");
          break;
        }

      case R.id.mc_TakeoffInAutoBtn:
      case R.id.mc_autoBtn:
        drone.changeVehicleMode(VehicleMode.PLANE_AUTO);
        eventBuilder
            .setAction(ACTION_FLIGHT_ACTION_BUTTON)
            .setLabel(VehicleMode.PLANE_AUTO.getLabel());
        break;

      case R.id.mc_follow:
        {
          toggleFollowMe();
          break;
        }

      default:
        eventBuilder = null;
        break;
    }

    if (eventBuilder != null) {
      GAUtils.sendEvent(eventBuilder);
    }
  }