Gimbal Function

2023-07-18
No Rating

Illustrate

  • Only payload devices developed with SkyPort support the gimbal function using PSDK.
  • X-Port supports developers to adjust configuration parameters using DJI Assistant 2 (version 2.0.11 and above).

Overview

Using the "gimbal control" function of PSDK, the developer needs to design the gimbal of the payload device and develop the program to control the gimbal. The Mobile App and remote control developed by MSDK can control the payload device with gimbal function developed based on PSDK, and obtain relevant information of the payload device, such as attitude, etc.

Basic Concepts

Gimbal status information

The gimbal-type load device developed using PSDK needs to report the gimbal status, current attitude and calibration status according to the specified requirements, so that the user's Mobile App or airborne computer can realize precise control according to the gimbal status. Please refer to the PSDK API documentation for the method and related details of getting the gimbal status.

Joint angle and attitude angle

Gimbal joint and gimbal joint angle

The joints of the gimbal are shown in Figure 1. The joints of the gimbal are the structural parts on the gimbal that drive the load equipment to rotate: the gimbal motor, and the joint angle of the gimbal is the angle at which the gimbal motor rotates. This tutorial uses the body coordinate system to describe the joint angles of the gimbal.

Figure 1. Gimbal joint

Gimbal attitude and Gimbal attitude angle

The attitude of the gimbal is shown in Figure 2. The attitude of the gimbal is shown in Figure 2. According to the user's control instructions, the gimbal can adjust the attitude; The angle of the payload, this angle is also called Euler angle.

Figure 2. Gimbal attitude

Gimbal mode

The gimbal mode determines how the gimbal rotates when it follows the movement of the drone:

  • Free mode: When the attitude of the drone changes, the gimbal will not turn.
  • FPV mode: When the attitude of the drone changes, the gimbal will rotate the pan axis and roll axis to ensure that the current field of view of the payload will not change.
  • YAW follow mode: In this mode, the pan-tilt's pan axis will follow the drone's pan axis.

Note: In the above three modes, other modules in the drone system (gimbal control commands during flight), the remote controller and the Mobile App can control the rotation of the gimbal.

Gimbal control

control mode

There are three ways to control the rotation of the gimbal:

  • Relative angle control: The gimbal developed with PSDK rotates the specified angle within the specified time according to the ** specified angle ** specified by the user.
  • Absolute angle control: The gimbal developed with PSDK will rotate from the current position to the specified position within the specified time according to the user's instructions.
  • Speed control: The user can control the rotation speed of the gimbal developed with PSDK.

illustrate

  • In the angle control mode, the rotation time of the gimbal is limited by the maximum rotation speed and acceleration of the gimbal, and the actual rotation angle is limited by the limit angle of the gimbal.
  • In speed control mode, the gimbal rotates for 0.5s according to the speed specified by the user. When the gimbal rotates to the limit angle, it will stop rotating.

Control permission

For details on gimbal control permissions, see Table 1. gimbal Control Permissions.

  • Control rules:
    • The control action with low priority can control the gimbal only after the control action with high priority is finished;
    • High-priority control actions can preempt control of low-priority control actions;
    • Control scenarios with the same priority will seize the control right in the order of starting control, and control scenarios with a later starting time cannot seize the control right.
  • Permission release
    • After the control module completes the control of the gimbal, it will release the control right;
    • If the control module does not release the control right after completing the control of the gimbal, the gimbal developed with PSDK will automatically release the control right within the specified time after the gimbal rotation ends.

Table 1. gimbal Control Permissions

permission rolepermission levelgimbal movement durationpermission timeout release time
Remote control gimbal rocker10500 ms
MSDK gimbal control commands1specified by the control command2000 ms
DJI APP gimbal control commands20500 ms
payload coordination instruction2specified by the control command
MSDK gimbal speed command20500 ms
gimbal control commands during flight2specified by the control command

Smoothness

The smoothness of the gimbal refers to the urgency of the gimbal's response. The gimbal developed with PSDK supports users to set the smoothness control coefficient through DJI Pilot and the Mobile App developed based on MSDK to realize the slow start and stop of the gimbal.

  • Smooth control coefficient: The smooth control coefficient determines the maximum acceleration of the gimbal rotation.
  • Maximum acceleration of gimbal rotation = 10000 × (0.8 ^ (1 + X)) deg/s^2 (X is the smoothing control coefficient)

Max speed percentage

  • Maximum speed percentage: The maximum speed percentage of the gimbal determines the maximum speed of the gimbal's rotation.

  • The actual maximum rotation speed of the gimbal = default maximum speed × maximum speed percentage

    Description: The developer can set the default maximum gimbal rotation speed according to the actual use needs.

Angle fine-tuning

The gimbal developed with PSDK allows users to finely adjust the joint angle of the gimbal through DJI Pilot and the Mobile App developed based on MSDK. The adjustment results can also be stored in the payload device as calibration parameters to reduce the gimbal’s angle. various errors.

Gimbal limit function

In order to prevent the gimbal from being accidentally damaged due to structural interference or interfering with the drone's flight mission when the gimbal is working, be sure to set mechanical and software limits for the gimbal.

  • Mechanical limit: The mechanical limit is determined by the physical form and design structure of the gimbal-type load device. For details, please refer to Standard Statementopen in new window.

  • Software limit: The developer can set the software limit according to the actual use requirements:

    • Set the Euler angle limit of the gimbal pitch axis, roll axis and pan axis;
    • Set the Euler angle extension angle limit of the pitch axis;
    • Set the gimbal joint angle limit.

    hint

    • After using the tilt axis angle range extension function, the Euler angle limit of the gimbal tilt axis can be set as the default limit or the extended limit.
    • When the joint angle of the gimbal reaches the limit, using DJI Pilot and the Mobile App developed based on MSDK will receive a prompt message that the gimbal rotates to the limit angle.

Gimbal reset

The gimbal-type load device developed with PSDK supports users to reset the gimbal through DJI Pilot and the Mobile App developed based on MSDK, and reset the gimbal's attitude to the initial state.

  • Pan axis reset: reset the pan/tilt pan axis angle to the sum of the drone pan axis angle and the pan tilt pan axis fine-tuning angle.
  • Pitch axis and pan axis reset: reset the gimbal pitch axis angle to the fine-tuning angle, reset the gimbal pan axis angle to the sum of the drone pan axis angle and the gimbal pan axis fine-tuning angle.
  • Reset the yaw and pitch axes of the gimbal: reset the angle of the gimbal's yaw axis to the sum of the drone's yaw axis and the gimbal's fine-tuning angle. Reset the gimbal pitch axis to the sum of -90° and the gimbal fine-tuning angle (the gimbal is down), and the sum of 90° and the gimbal's fine-tuning angle (the gimbal is up).
  • Reset the yaw axis of the gimbal to the sum of -90° and the gimbal fine-tuning angle (the gimbal is down), and the sum of 90° and the gimbal's fine-tuning angle (the gimbal is up).

Implement gimbal function

Developers are requested to construct a function to realize the control function of the gimbal-type load device according to the structure T_DjiGimbalCommonHandler in the PSDK according to the selected development platform and the actual use requirements of the industry application, and register the function of the gimbal control function to After the interface specified in the PSDK, the user can control the gimbal-type load device developed based on the PSDK to perform the specified actions by using DJI Pilot or the Mobile App developed based on the MSDK.

    
	s_commonHandler.GetSystemState = GetSystemState;
    s_commonHandler.GetAttitudeInformation = GetAttitudeInformation;
    s_commonHandler.GetCalibrationState = GetCalibrationState;
    s_commonHandler.GetRotationSpeed = GetRotationSpeed;
    s_commonHandler.GetJointAngle = GetJointAngle;

    s_commonHandler.Rotate = DjiTest_GimbalRotate;
    s_commonHandler.StartCalibrate = StartCalibrate;
    s_commonHandler.SetControllerSmoothFactor = SetControllerSmoothFactor;
    s_commonHandler.SetPitchRangeExtensionEnabled = SetPitchRangeExtensionEnabled;
    s_commonHandler.SetControllerMaxSpeedPercentage = SetControllerMaxSpeedPercentage;
    s_commonHandler.RestoreFactorySettings = RestoreFactorySettings;
    s_commonHandler.SetMode = SetMode;
    s_commonHandler.Reset = Reset;
    s_commonHandler.FineTuneAngle = FineTuneAngle;

Using the gimbal control function

To use the gimbal control function, you need to first realize the gimbal control function, then realize the gimbal limit function, adjust the gimbal's attitude, target angle and limit mark according to the gimbal mode, and finally realize the gimbal calibration function to calibrate the gimbal.

Note: When using PSDK to develop the gimbal function of the payload device, please use SkyPort V2 or SkyPort, if the development tool you use is X-Port, please read X-Port Functionopen in new window.

Using the gimbal Management Function

1. gimbal control function module initialization

Before using the "gimbal control" function, you need to initialize the gimbal control function module to ensure that the gimbal control function can run normally.

djiStat = DjiGimbal_Init();
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
    USER_LOG_ERROR("init gimbal module error: 0x%08llX", djiStat);
}

2. Register the gimbal control function

When using the gimbal control function of PSDK to control the gimbal load device, the developer needs to register the gimbal control function to the specified interface.

djiStat = DjiGimbal_RegCommonHandler(&s_commonHandler);
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
    USER_LOG_ERROR("gimbal register common handler error: 0x%08llX", djiStat);
}

3. Get the status information of the gimbal

In order to facilitate the user to control the gimbal to perform corresponding actions, it is necessary to call the GetSystemState interface to obtain the state of the gimbal.

static T_DjiReturnCode GetSystemState(T_DjiGimbalSystemState *systemState)
{
    T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();

    if (osalHandler->MutexLock(s_commonMutex) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
        USER_LOG_ERROR("mutex lock error");
        return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
    }

    *systemState = s_systemState;

    if (osalHandler->MutexUnlock(s_commonMutex) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
        USER_LOG_ERROR("mutex unlock error");
        return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
    }

    return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}

4. Construct a callback function to calculate the rotation speed of the gimbal

Construct a callback function to calculate the rotation speed of the gimbal, adjust the attitude of the gimbal, and record the target angle and rotation speed of the gimbal.

T_DjiReturnCode DjiTest_GimbalRotate(E_DjiGimbalRotationMode rotationMode,
                                     T_DjiGimbalRotationProperty rotationProperty,
                                     T_DjiAttitude3d rotationValue)
{
    T_DjiReturnCode djiStat;
    T_DjiReturnCode returnCode = DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
    T_DjiAttitude3d targetAttitudeDTemp = {0};
    T_DjiAttitude3f targetAttitudeFTemp = {0};
    T_DjiAttitude3d speedTemp = {0};
    T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();

    USER_LOG_DEBUG("gimbal rotation value invalid flag: pitch %d, roll %d, yaw %d.",
                   rotationProperty.rotationValueInvalidFlag.pitch,
                   rotationProperty.rotationValueInvalidFlag.roll,
                   rotationProperty.rotationValueInvalidFlag.yaw);

    if (osalHandler->MutexLock(s_attitudeMutex) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
        USER_LOG_ERROR("mutex lock error");
        return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
    }

    if (osalHandler->MutexLock(s_commonMutex) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
        USER_LOG_ERROR("mutex lock error");
        returnCode = DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
        goto out2;
    }

    switch (rotationMode) {
        case DJI_GIMBAL_ROTATION_MODE_RELATIVE_ANGLE:
            USER_LOG_INFO("gimbal relative rotate angle: pitch %d, roll %d, yaw %d.", rotationValue.pitch,
                          rotationValue.roll, rotationValue.yaw);
            USER_LOG_DEBUG("gimbal relative rotate action time: %d.",
                           rotationProperty.relativeAngleRotation.actionTime);

            if (s_rotatingFlag == true) {
                USER_LOG_WARN("gimbal is rotating.");
                goto out1;
            }

            targetAttitudeDTemp.pitch =
                rotationProperty.rotationValueInvalidFlag.pitch == true ? s_attitudeInformation.attitude.pitch : (
                    s_attitudeInformation.attitude.pitch + rotationValue.pitch);
            targetAttitudeDTemp.roll =
                rotationProperty.rotationValueInvalidFlag.roll == true ? s_attitudeInformation.attitude.roll : (
                    s_attitudeInformation.attitude.roll + rotationValue.roll);
            targetAttitudeDTemp.yaw =
                rotationProperty.rotationValueInvalidFlag.yaw == true ? s_attitudeInformation.attitude.yaw : (
                    s_attitudeInformation.attitude.yaw + rotationValue.yaw);

            targetAttitudeFTemp.pitch = targetAttitudeDTemp.pitch;
            targetAttitudeFTemp.roll = targetAttitudeDTemp.roll;
            targetAttitudeFTemp.yaw = targetAttitudeDTemp.yaw;
            DjiTest_GimbalAngleLegalization(&targetAttitudeFTemp, s_aircraftAttitude, NULL);
            targetAttitudeDTemp.pitch = targetAttitudeFTemp.pitch;
            targetAttitudeDTemp.roll = targetAttitudeFTemp.roll;
            targetAttitudeDTemp.yaw = targetAttitudeFTemp.yaw;

            s_targetAttitude = targetAttitudeDTemp;
            s_rotatingFlag = true;
            s_controlType = TEST_GIMBAL_CONTROL_TYPE_ANGLE;

            djiStat = DjiTest_GimbalCalculateSpeed(s_attitudeInformation.attitude, s_targetAttitude,
                                                   rotationProperty.relativeAngleRotation.actionTime, &s_speed);
            if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
                USER_LOG_ERROR("calculate gimbal rotation speed error: 0x%08llX.", djiStat);
                returnCode = djiStat;
                goto out1;
            }

            break;
        case DJI_GIMBAL_ROTATION_MODE_ABSOLUTE_ANGLE:
            USER_LOG_INFO("gimbal absolute rotate angle: pitch %d, roll %d, yaw %d.", rotationValue.pitch,
                          rotationValue.roll, rotationValue.yaw);
            USER_LOG_DEBUG("gimbal absolute rotate action time: %d.",
                           rotationProperty.absoluteAngleRotation.actionTime);
            if (rotationProperty.absoluteAngleRotation.jointAngleValid) {
                USER_LOG_DEBUG("gimbal joint angles: pitch %d, roll %d, yaw %d.",
                               rotationProperty.absoluteAngleRotation.jointAngle.pitch,
                               rotationProperty.absoluteAngleRotation.jointAngle.roll,
                               rotationProperty.absoluteAngleRotation.jointAngle.yaw);
            }

            if (s_rotatingFlag == true) {
                USER_LOG_WARN("gimbal is rotating.");
                goto out1;
            }

            targetAttitudeDTemp.pitch =
                rotationProperty.rotationValueInvalidFlag.pitch == true ? s_attitudeInformation.attitude.pitch
                                                                        : rotationValue.pitch;
            targetAttitudeDTemp.roll =
                rotationProperty.rotationValueInvalidFlag.roll == true ? s_attitudeInformation.attitude.roll
                                                                       : rotationValue.roll;
            targetAttitudeDTemp.yaw =
                rotationProperty.rotationValueInvalidFlag.yaw == true ? s_attitudeInformation.attitude.yaw
                                                                      : rotationValue.yaw;

            targetAttitudeFTemp.pitch = targetAttitudeDTemp.pitch;
            targetAttitudeFTemp.roll = targetAttitudeDTemp.roll;
            targetAttitudeFTemp.yaw = targetAttitudeDTemp.yaw;
            DjiTest_GimbalAngleLegalization(&targetAttitudeFTemp, s_aircraftAttitude, NULL);
            targetAttitudeDTemp.pitch = targetAttitudeFTemp.pitch;
            targetAttitudeDTemp.roll = targetAttitudeFTemp.roll;
            targetAttitudeDTemp.yaw = targetAttitudeFTemp.yaw;

            s_targetAttitude = targetAttitudeDTemp;
            s_rotatingFlag = true;
            s_controlType = TEST_GIMBAL_CONTROL_TYPE_ANGLE;

            djiStat = DjiTest_GimbalCalculateSpeed(s_attitudeInformation.attitude, s_targetAttitude,
                                                   rotationProperty.absoluteAngleRotation.actionTime, &s_speed);
            if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
                USER_LOG_ERROR("calculate gimbal rotation speed error: 0x%08llX.", djiStat);
                returnCode = djiStat;
                goto out1;
            }

            break;
        case DJI_GIMBAL_ROTATION_MODE_SPEED:
            USER_LOG_INFO("gimbal rotate speed: pitch %d, roll %d, yaw %d.", rotationValue.pitch,
                          rotationValue.roll, rotationValue.yaw);

            if (s_rotatingFlag == true && s_controlType == TEST_GIMBAL_CONTROL_TYPE_ANGLE) {
                USER_LOG_WARN("gimbal is rotating.");
                goto out1;
            }

            memcpy(&speedTemp, &rotationValue, sizeof(T_DjiAttitude3d));
            DjiTest_GimbalSpeedLegalization(&speedTemp);
            s_speed = speedTemp;

            if (rotationValue.pitch != 0 || rotationValue.roll != 0 || rotationValue.yaw != 0) {
                s_rotatingFlag = true;
                s_controlType = TEST_GIMBAL_CONTROL_TYPE_SPEED;
            } else {
                s_rotatingFlag = false;
            }

            break;
        default:
            USER_LOG_ERROR("gimbal rotation mode invalid: %d.", rotationMode);
            returnCode = DJI_ERROR_SYSTEM_MODULE_CODE_NONSUPPORT;
            goto out1;
    }

out1:
    if (osalHandler->MutexUnlock(s_commonMutex) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
        USER_LOG_ERROR("mutex unlock error");
        returnCode = DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
        goto out2;
    }

out2:
    if (osalHandler->MutexUnlock(s_attitudeMutex) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
        USER_LOG_ERROR("mutex unlock error");
        return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
    }

    return returnCode;
}

5. Control the gimbal rotation

the payload device converts the relative angle control amount, absolute angle control amount or speed control amount into the speed of controlling the rotation of the gimbal according to the attitude and rotation speed of the gimbal, and controls the rotation of the gimbal according to the speed, as shown in Figure 3. Show.

nextAttitude.pitch =
            (float) s_attitudeHighPrecision.pitch + (float) s_speed.pitch / (float) PAYLOAD_GIMBAL_TASK_FREQ;
        nextAttitude.roll =
            (float) s_attitudeHighPrecision.roll + (float) s_speed.roll / (float) PAYLOAD_GIMBAL_TASK_FREQ;
        nextAttitude.yaw = (float) s_attitudeHighPrecision.yaw + (float) s_speed.yaw / (float) PAYLOAD_GIMBAL_TASK_FREQ;

        if (s_controlType == TEST_GIMBAL_CONTROL_TYPE_ANGLE) {
            nextAttitude.pitch =
                (nextAttitude.pitch - s_targetAttitude.pitch) * s_speed.pitch >= 0 ? s_targetAttitude.pitch
                                                                                   : nextAttitude.pitch;
            nextAttitude.roll = (nextAttitude.roll - s_targetAttitude.roll) * s_speed.roll >= 0 ? s_targetAttitude.roll
                                                                                                : nextAttitude.roll;
            nextAttitude.yaw =
                (nextAttitude.yaw - s_targetAttitude.yaw) * s_speed.yaw >= 0 ? s_targetAttitude.yaw : nextAttitude.yaw;
        }

        DjiTest_GimbalAngleLegalization(&nextAttitude, s_aircraftAttitude, &s_attitudeInformation.reachLimitFlag);
        s_attitudeInformation.attitude.pitch = nextAttitude.pitch;
        s_attitudeInformation.attitude.roll = nextAttitude.roll;
        s_attitudeInformation.attitude.yaw = nextAttitude.yaw;

        s_attitudeHighPrecision.pitch = nextAttitude.pitch;
        s_attitudeHighPrecision.roll = nextAttitude.roll;
        s_attitudeHighPrecision.yaw = nextAttitude.yaw;

        if (s_controlType == TEST_GIMBAL_CONTROL_TYPE_ANGLE) {
            if (memcmp(&s_attitudeInformation.attitude, &s_targetAttitude, sizeof(T_DjiAttitude3d)) == 0) {
                s_rotatingFlag = false;
            }
        } else if (s_controlType == TEST_GIMBAL_CONTROL_TYPE_SPEED) {
            if ((s_attitudeInformation.reachLimitFlag.pitch == true || s_speed.pitch == 0) &&
                (s_attitudeInformation.reachLimitFlag.roll == true || s_speed.roll == 0) &&
                (s_attitudeInformation.reachLimitFlag.yaw == true || s_speed.yaw == 0)) {
                s_rotatingFlag = false;
            }
        }

Figure 3. gimbal Control

Adjust the parameters when the gimbal is in different modes

Developers can adjust the attitude, target angle and arrival limit mark of the gimbal when it is indifferent modes according to the actual use requirements.

  • In FPV mode:
    • Adjust the gimbal attitude: superimpose the change of the drone's attitude on the roll axis and pan axis of the gimbal;
    • Adjust the target angle of the gimbal rotation: When the gimbal rotates, the attitude change of the drone is superimposed on the roll axis and pan axis of the gimbal.
  • In YAW mode:
    • Adjust the gimbal attitude: superimpose the change of the drone's attitude on the heading axis of the gimbal;
    • Adjust the target angle of the gimbal rotation: When the gimbal rotates, the attitude change of the drone is superimposed on the gimbal's heading axis.
  • Adjust the rotation range of the gimbal attitude and the target angle, and the payload device can calculate the limit mark of the gimbal.
switch (s_systemState.gimbalMode) {
    case PSDK_GIMBAL_MODE_FREE:
        break;
    case PSDK_GIMBAL_MODE_FPV:
        s_attitudeInformation.attitude.roll += (s_aircraftAttitude.roll - s_lastAircraftAttitude.roll);
        s_attitudeInformation.attitude.yaw += (s_aircraftAttitude.yaw - s_lastAircraftAttitude.yaw);

        s_attitudeHighPrecision.roll += (float) (s_aircraftAttitude.roll - s_lastAircraftAttitude.roll);
        s_attitudeHighPrecision.yaw += (float) (s_aircraftAttitude.yaw - s_lastAircraftAttitude.yaw);

        if (s_rotatingFlag == true && s_controlType == TEST_GIMBAL_CONTROL_TYPE_ANGLE) {
            s_targetAttitude.roll += (s_aircraftAttitude.roll - s_lastAircraftAttitude.roll);
            s_targetAttitude.yaw += (s_aircraftAttitude.yaw - s_lastAircraftAttitude.yaw);
        }
        break;
    case PSDK_GIMBAL_MODE_YAW_FOLLOW:
        s_attitudeInformation.attitude.yaw += (s_aircraftAttitude.yaw - s_lastAircraftAttitude.yaw);

        s_attitudeHighPrecision.yaw += (float) (s_aircraftAttitude.yaw - s_lastAircraftAttitude.yaw);

        if (s_rotatingFlag == true && s_controlType == TEST_GIMBAL_CONTROL_TYPE_ANGLE) {
            s_targetAttitude.yaw += (s_aircraftAttitude.yaw - s_lastAircraftAttitude.yaw);
        }
        break;
    default:
        PsdkLogger_UserLogError("gimbal mode invalid: %d.", s_systemState.gimbalMode);
}
s_lastAircraftAttitude = s_aircraftAttitude;

attitudeFTemp.pitch = s_attitudeInformation.attitude.pitch;
attitudeFTemp.roll = s_attitudeInformation.attitude.roll;
attitudeFTemp.yaw = s_attitudeInformation.attitude.yaw;
PsdkTest_GimbalAngleLegalization(&attitudeFTemp, s_aircraftAttitude, &s_attitudeInformation.reachLimitFlag);
s_attitudeInformation.attitude.pitch = attitudeFTemp.pitch;
s_attitudeInformation.attitude.roll = attitudeFTemp.roll;
s_attitudeInformation.attitude.yaw = attitudeFTemp.yaw;

PsdkTest_GimbalAngleLegalization(&s_attitudeHighPrecision, s_aircraftAttitude, NULL);

attitudeFTemp.pitch = s_targetAttitude.pitch;
attitudeFTemp.roll = s_targetAttitude.roll;
attitudeFTemp.yaw = s_targetAttitude.yaw;
PsdkTest_GimbalAngleLegalization(&attitudeFTemp, s_aircraftAttitude, NULL);
s_targetAttitude.pitch = attitudeFTemp.pitch;
s_targetAttitude.roll = attitudeFTemp.roll;
s_targetAttitude.yaw = attitudeFTemp.yaw;

Using the gimbal calibration function

In order to facilitate users to control the gimbal more accurately, it is recommended that developers implement the gimbal calibration function when developing a load device with gimbal function.

1. Using the gimbal calibration function

If you want to use the gimbal calibration function, please implement the gimbal calibration function first, and register the gimbal calibration function to the specified interface, so that users can use DJI Pilot or the Mobile App developed based on MSDK to calibrate the gimbal function. load equipment.

static T_PsdkReturnCode StartCalibrate(void)
{
    T_PsdkReturnCode psdkStat;

    PsdkLogger_UserLogDebug("start calibrate gimbal.");

    psdkStat = PsdkOsal_GetTimeMs(&s_calibrationStartTime);
    if (psdkStat != PSDK_RETURN_CODE_OK) {
        PsdkLogger_UserLogError("get start time error: %lld.", psdkStat);
    }

    if (PsdkOsal_MutexLock(s_calibrationMutex) != PSDK_RETURN_CODE_OK) {
        PsdkLogger_UserLogError("mutex lock error");
        return PSDK_RETURN_CODE_ERR_UNKNOWN;
    }

    s_calibrationState.calibratingFlag = true;
    s_calibrationState.progress = 0;
    s_calibrationState.stage = PSDK_GIMBAL_CALIBRATION_STAGE_PROCRESSING;

    if (PsdkOsal_MutexUnlock(s_calibrationMutex) != PSDK_RETURN_CODE_OK) {
        PsdkLogger_UserLogError("mutex unlock error");
        return PSDK_RETURN_CODE_ERR_UNKNOWN;
    }

    return PSDK_RETURN_CODE_OK;
}

2. gimbal calibration status update

After the payload device performs the gimbal calibration function, it will record the calibration status of the gimbal, and the Mobile App developed based on MSDK can obtain the calibration status of the gimbal.

 // calibration
        if (s_calibrationState.calibratingFlag != true)
            goto unlockCalibrationMutex;

        progressTemp = (currentTime - s_calibrationStartTime) * 100 / PAYLOAD_GIMBAL_CALIBRATION_TIME_MS;
        if (progressTemp >= 100) {
            s_calibrationState.calibratingFlag = false;
            s_calibrationState.currentCalibrationProgress = 100;
            s_calibrationState.currentCalibrationStage = PSDK_GIMBAL_CALIBRATION_STAGE_COMPLETE;
        }

unlockCalibrationMutex:
        if (PsdkOsal_MutexUnlock(s_calibrationMutex) != PSDK_RETURN_CODE_OK) {
            PsdkLogger_UserLogError("mutex unlock error");
            continue;
        }

After using the "Gimbal Automatic Calibration" function in DJI Pilot and the Mobile App developed based on MSDK, the payload device developed using PSDK will receive the gimbal calibration command and calibrate the gimbal, as shown in Figure 4 and Figure 5.

Figure 4. Gimbal calibration (1)

Figure 5. Gimbal calibration (2)

If you have any comments or confusion about our documentation, you can click here to give feedback and we will get back to you as soon as possible.