M350b版本

This commit is contained in:
xin
2025-12-24 09:19:07 +08:00
parent 257708ae42
commit 7396728ea7
627 changed files with 42382 additions and 250967 deletions

View File

@ -46,39 +46,57 @@ typedef struct {
} T_DjiMobileAppInfo;
/**
* @brief Some base information of aircraft system, mainly including some constant parameters information of system.
* @brief Basic information about the aircraft system, mainly including some constant parameters information.
*/
typedef struct {
E_DjiAircraftSeries aircraftSeries; /*!< Aircraft series. */
E_DjiMountPositionType mountPositionType; /*!< Mount position type. */
E_DjiAircraftType aircraftType; /*!< Aircraft type. */
E_DjiSdkAdapterType djiAdapterType; /*!< DJI adapter type. */
E_DjiMountPosition mountPosition; /*!< Payload mount position. */
} T_DjiAircraftInfoBaseInfo;
/**
* @brief Aircraft version information.
*/
typedef struct {
uint8_t debugVersion;
uint8_t modifyVersion;
uint8_t minorVersion;
uint8_t majorVersion;
} T_DjiAircraftVersion;
/* Exported functions --------------------------------------------------------*/
/**
* @brief Get base information of aircraft system, including aircraft type and DJI adapter type.
* @param baseInfo: pointer to memory space used to store base information of the aircraft system.
* @brief Basic information about the aircraft system, including aircraft type and DJI adapter type.
* @param baseInfo: Pointer to a memory space where the aircraft's basic information will be stored.
* @return Execution result.
*/
T_DjiReturnCode DjiAircraftInfo_GetBaseInfo(T_DjiAircraftInfoBaseInfo *baseInfo);
/**
* @brief Get information related to mobile APP.
* @note The mobile APP language and screen type is unknown if RC or APP is not connected to the aircraft system.
* @param mobileAppInfo: pointer to memory space used to store information related to mobile APP.
* @brief Get information related to mobile app.
* @note Returns unknown for app language and screen type if the RC or app is not connected to the aircraft system.
* @param mobileAppInfo: Pointer to a memory space where the mobile app information will be stored.
* @return Execution result.
*/
T_DjiReturnCode DjiAircraftInfo_GetMobileAppInfo(T_DjiMobileAppInfo *mobileAppInfo);
/**
* @brief Get connection status of payload and aircraft.
* @brief Get connection status between the payload and the aircraft.
* @note Update period: 1Hz
* @param isConnected: pointer to connection status.
* @param isConnected: Pointer to connection status.
* @return Execution result.
*/
T_DjiReturnCode DjiAircraftInfo_GetConnectionStatus(bool *isConnected);
/**
* @brief Get version of the aircraft.
* @param aircraftVersion: Pointer to aircraft version.
* @return Execution result.
*/
T_DjiReturnCode DjiAircraftInfo_GetAircraftVersion(T_DjiAircraftVersion *aircraftVersion);
#ifdef __cplusplus
}
#endif

File diff suppressed because it is too large Load Diff

View File

@ -56,27 +56,26 @@ typedef struct {
/* Exported functions --------------------------------------------------------*/
/**
* @brief Initialize the Payload SDK core in blocking mode.
* @note The call location of this interface requires special attention, The call needs to be completed after the
* registration of console/OSAL handler functions/HAL handler functions are completed. At the same time, it must be
* initialized at the beginning of calling other functional module interfaces. You need to fill in the developer
* information correctly to ensure the initialization is successful. For additional instructions, please refer to the
* tutorial“PSDK Initialization”.
* @note This function does not return until the correct aircraft type and PSDK adapter type is obtained. The logic ensures
* @note The order of calling this call is crucial. It must be done after registering console/OSAL/HAL handler functions
* It must be done after registering console/OSAL/HAL handler functions and before using other functional module
* interfaces. Correctly fill in the developer information to ensure successful initialization. See the
* See the "PSDK Initialization" tutorial for more.
* This function does not return until the correct aircraft type and PSDK adapter type is obtained. The logic ensures
* that aircraft and PSDK adapter have been started up normally before PSDK functional module and user's program run.
* General execution time of this function is 2~4 seconds.
* General execution time of this function is 2-4 seconds.
* @param userInfo: pointer to the PSDK application information.
* @return Execution result.
*/
T_DjiReturnCode DjiCore_Init(const T_DjiUserInfo *userInfo);
/**
* @brief Set an alias that satisfies the condition for DJI application or product.
* @details Alias will display in DJI Pilot, if exist.
* @brief Sets an alias for a DJI application or product that meets the condition for DJI application or product.
* If an alias exists, it will be displayed in DJI Pilot.
* @note Still need to pass in correct DJI APP name that is obtained from DJI SDK developer website to DjiCore_Init()
* interface. The DJI APP name will be used to bind or verification.
* @note Alias will be effective after a while, and the max value is 1s.
* @param productAlias: pointer to product alias string, and alias end with '\0'. The max length of the string is 31. If
* length of alias string is greater than 31, alias string will be truncated and passed in.
* interface. The DJI APP name will be used to bind and verification.
* The alias will take effect after a short delay, up to a maximum of 1 second.
* @param productAlias: A pointer to the product alias string, which must end with '\0'. The maximum length of the string is 31 characters.
* If the alias string exceeds 31 characters, it will be truncated before being passed in.
* @return Execution result.
*/
T_DjiReturnCode DjiCore_SetAlias(const char *productAlias);
@ -99,7 +98,7 @@ T_DjiReturnCode DjiCore_SetSerialNumber(const char *productSerialNumber);
/**
* @brief Notify that the Payload SDK core application starts.
* @note The call location of this interface requires special attention, The call needs to be completed after all the
* @note The order of calling this interface requires special attention, The call needs to be completed after all the
* module initialize and register interfaces.
* @return Execution result.
*/

View File

@ -312,27 +312,143 @@ extern "C" {
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_CAMERA_FOCAL_DISTANCE_INVALID, "Focal distance of camera focalize function exceed valid range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_CAMERA_EXEC_FAIL, "This err code indicate camera fail to exec coressponding cmd and the low 8 bit", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_GIMBAL_RESV, "Reserved error code", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_GIMBAL_INVALID_RPY_ANGLE_CTRL_CMD, "Gimbal roll pitch yaw angle ctrl cmd param invalid ", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_GIMBAL_INVALID_RPY_ANGLE_CTRL_CMD, "Gimbal roll pitch yaw angle ctrl cmd param invalid ", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_GIMBAL_INVALID_DURATION_CMD, "Gimbal duration param invalid unable to exec. ", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_GIMBAL_FAIL_TO_ARRIVE_TGT_ANGLE, "Gimbal fail to arrive target angle . ", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_GIMBAL_FAIL_TO_SEND_CMD_TO_GIMBAL, "Fail to send cmd to gimbal for gimbal is busy or no gimbal. ", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_GIMBAL_THIS_INDEX_OF_GIMBAL_NOT_DOING_UNIFORM_CTRL , "Fail to stop gimbal uniform ctrl because index error. ", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_FLIGHT_RESV, "Reserved error code", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_FLIGHT_YAW_INVALID_YAW_ANGLE, "Yaw angle is lager max yaw angle. ", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_FLIGHT_YAW_TO_TGT_ANGLE_TIMEOUT, "Failed to target yaw angle because of timeout. ", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_FLIGHT_YAW_TO_TGT_ANGLE_TIMEOUT, "Failed to target yaw angle because of timeout. ", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_FLIGHT_ACTION_YAW_OCCUPIED, "Failed to target yaw angle because of timeout. ", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_FLIGHT_CUR_AND_TGT_VEL_CLE_STATUE_EQUAL, "Failed to current and target vel not equal. ", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_PAYLOAD_RESV, "Failed to payload reserved error code. ", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_PAYLOAD_FAIL_TO_SEND_CMD_TO_PAYLOAD, "Failed to sned cmd to payload. ", NULL}, \
{DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_PAYLOAD_EXEC_FAILED, "Failed to execute payload actuator. ", NULL}, \
/* waypoint v3 module error message */ \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_COMMON_SUCCESS, "Execute waypoint v3 cmd successfully. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_MISSION_ID_NOT_EXIST, "Execute waypoint v3 mission id not match. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_WAYLINE_INFO_ERROR , "Execute waypoint v3 wayline info error. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_WPMZ_FILE_VERSION_NOT_MATCH, "Execute waypoint v3 wpmz file not match. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_WPMZ_FILE_LOAD_ERROR, "Load waypoint v3 wpmz file error. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_NO_BREAK_INFO, "Execute waypoint v3 no break info error. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CMD_INVALID, "Execute waypoint v3 cmd invalid. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_START_WAYLINE_WHEN_WAYLINE_RUNNING, "Cannot start wayline when wayline running. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_BREAK_WAYLINE_IN_CUR_STATE, "Cannot break wayline in current state. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_STOP_WAYLINE_WHEN_WAYLINE_NOT_RUNNING, "Cannot stop wayline when wayline not running. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_BREAK_WAYLINE_WHEN_WAYLINE_NOT_RUNNING, "Cannot break wayline when wayline not running. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_REQUEST_DRONE_CONTROL, "Flight mission conflict, unable to obtain control auth of the aircraft. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_RESUME_WAYLINE_IN_CUR_STATE, "Failed to resume wayline in current state. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_HEIGHT_LIMIT, "Execute waypoint v3 failed due to height limit. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_RADIUS_LIMIT, "Execute waypoint v3 failed due to radius limit. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CROSS_FLYLIMIT_AERA, "Execute waypoint v3 failed due to cross flylimit area. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_LOW_LIMIT, "Execute waypoint v3 failed due to low limit. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_OBSTACAL_STOP, "Execute waypoint v3 failed due to obstacal stop. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_RTK_DISCONNECT, "Execute waypoint v3 failed due to rtk disconnect. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_BOUNDARY_LIMIT, "Execute waypoint v3 failed due to boundary limit. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_RC_PITCH_ROLL_BREAK, "Execute waypoint v3 failed due to rc pitch roll break. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_AIRPORT_HEIGHT_LIMIT, "Execute waypoint v3 failed due to airport height limit. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_REQUEST_TAKEOFF_FAIL, "Failed to request take off. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_AUTOTAKEOFF_RUN_FAIL, "Failed to run auto take off. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_REQUEST_WAYLINE_FAIL, "Failed to request wayline. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_AGRO_PLAN_FAIL, "Failed to agro plan. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_REQUEST_QUICK_TAKEOFF_ASSIST_FAIL, "Failed to request quick take off assist. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_QUICK_TAKEOFF_ASSIST_RUN_FAIL, "Failed to run quick takeoff assist. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_VFENCE_LIMIT, "Execute waypoint v3 failed due to vfence limit. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_GPS_INVALID, "Execute waypoint v3 failed due to gps invalid. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_START_AT_CURRENT_RC_MODE, "Failed to start at current rc mode. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_HOME_POINT_NOT_RECORDED, "Execute waypoint v3 failed due to homepoint not recorded. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_LOWER_BATTERY, "Execute waypoint v3 failed due to lower battery. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_RETURN_HOME, "Execute waypoint v3 failed due to return home. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ADSB_ERROR, "Execute waypoint v3 failed due to adsb error. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_RC_LOST, "Execute waypoint v3 failed due to rc lost. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_RTK_NOT_READY, "Execute waypoint v3 failed due to rtk not ready. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_DRONE_IS_MOVING, "Execute waypoint v3 failed due to drone is moving. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_DRONE_ON_GROUND_MOTOR_ON, "Execute waypoint v3 failed due to drone on ground motor on. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_SURFACE_FOLLOW_CAMERA_INVALID, "Execute waypoint v3 failed due to surface follow camera invalid. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_SURFACE_FOLLOW_HEIGHT_INVALID, "Execute waypoint v3 failed due to surface follow height invalid.", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_SURFACE_FOLLOW_MAP_WRONG, "Execute waypoint v3 failed due to surface follow map wrong. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_HOMEPOINT_NOT_MATCH_RTK, "Execute waypoint v3 failed due to homepoint not match rtk. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_STRONG_WIND_GOHOME, "Execute waypoint v3 failed due to strong wind gohome. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_DRONE_CRITICAL_ERROR, "Execute waypoint v3 failed due to drone critical error. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_FIND_PAYLOAD, "Execute waypoint v3 failed due to cannot find payload. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_EXECUTION_FAILED, "Execute waypoint v3 failed due to action execution failed. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_FARM_NO_PESTICIDE, "Execute waypoint v3 failed due to farm no pesticide. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_RADAR_DISCONNECT, "Execute waypoint v3 failed due to radar disconnect. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_USER_EXIT, "Execute waypoint v3 failed due to user exit. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_USER_BREAK, "Execute waypoint v3 failed due to user break. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_USER_SET_GOHOME, "Execute waypoint v3 failed due to user set gohome. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_USER_AGRO_PLANNER_STATE_CHANGE, "Execute waypoint v3 failed due to user agro panner state change. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_USER_SWITCH_RC_MODE, "Execute waypoint v3 failed due to user switch rc mode. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INIT_FAIL, "Execute waypoint v3 failed due to traj init failed. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_JOB_EXIT_BUT_MIS_RUNNING, "Execute waypoint v3 failed due to traj job exit but mis running. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_ON_GROUND_MOTOR_ON_CANNOT_GO, "Execute waypoint v3 failed due to traj on ground motor is turn on. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_START_INDEX_OR_PROG, "Execute waypoint v3 failed due to traj invalid start index. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_CSYS_MODE, "Execute waypoint v3 failed due to traj invalid csys mode. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_HEIGHT_MODE, "Execute waypoint v3 failed due to traj invalid height mode. ", NULL},\
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_FLY_WP_MODE, "Execute waypoint v3 failed due to traj invalid fly wp mode. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_YAW_MODE, "Execute waypoint v3 failed due to traj invalid yaw mode. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_TURN_DIR_MODE, "Execute waypoint v3 failed due to traj invalid turn dir mode. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_WP_TYPE, "Execute waypoint v3 failed due to traj invalid wp type. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_FIR_LAS_WP_TYPE_ERROR, "Execute waypoint v3 failed due to fir las wp type error. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_GLOB_VEL_OUT_OF_RANGE, "Execute waypoint v3 failed due to traj wp global vel out of range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_WP_NUM_OUT_OF_RANGE, "Execute waypoint v3 failed due to traj wp num out of range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_LAT_LONG_OUT_OF_RANGE, "Execute waypoint v3 failed due to traj lat or lon out of range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_DAMP_DIS_OUT_OF_RANGE, "Execute waypoint v3 failed due to traj damp dis out of range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_MAX_VEL_OUT_OF_RANGE, "Execute waypoint v3 failed due to traj max vel out of range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_VEL_OUT_OF_RANGE, "Execute waypoint v3 failed due to traj vel out of range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_WP_YAW_OUT_OF_RANGE, "Execute waypoint v3 failed due to traj wp yaw out of range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_YAW_MODE_IN_VERT_SEGM, "Execute waypoint v3 failed due to traj invalid yaw mode in vert segm. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_WP_BREAK_INFO_MISSION_ID_CHANGED, "Execute waypoint v3 failed due to traj wp break info mission id changed. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_WP_BREAK_INFO_PROGRESS_OUT_OF_RANGE, "Execute waypoint v3 failed due to traj wp break info progress out of range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_WP_BREAK_INFO_INVALID_MISSION_STATE, "Execute waypoint v3 failed due to traj wp break info invalid mission state. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_WP_BREAK_INFO_WP_INDEX_OUT_OF_RANGE, "Execute waypoint v3 failed due to traj wp break info wp index out of range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_BREAK_LAT_LONG_OUT_OF_RANGE, "Execute waypoint v3 failed due to traj break lat or lon out of range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_BREAK_INFO_WP_YAW_OUT_OF_RANGE, "Execute waypoint v3 failed due to traj break info wp yaw out of range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_BREAK_INFO_FLAG , "Execute waypoint v3 failed due to traj invalid break info flag. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_GET_TRAJ_INFO_FAILED, "Execute waypoint v3 failed due to traj get info failed. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_GENERATE_FAIL, "Execute waypoint v3 failed due to traj generate failed. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_LIB_RUN_FAIL, "Execute waypoint v3 failed due to traj lib run failed. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_LIB_EMERGENCY_BRAKE, "Execute waypoint v3 failed due to traj lib emergency brake. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_NOT_FOUND, "Execute waypoint v3 failed due to action not found. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_INDEX_REPEATED, "Execute waypoint v3 failed due to action index repeated. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_INFO_SIZE_TOO_LONG_OR_TOO_SHORT, "Execute waypoint v3 failed due to size too long or too short. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_TREE_EMPTY, "Execute waypoint v3 failed due to action tree empty. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_TREE_LAYER_EMPTY, "Execute waypoint v3 failed due to action tree layer empty. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_ID_REPEATED, "Execute waypoint v3 failed due to action repeated. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_NODE_CHILDREN_NUM_LT_2, "Execute waypoint v3 failed due to action mode children num less than 2. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_INDEX_OUT_OF_RANGE, "Execute waypoint v3 failed due to action index out of range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_ID_IS_65535, "Execute waypoint v3 failed due to action id is 65535. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_NODE_CHILDNUM_SUM_NOT_EQ_NEXT_LAYER_SIZE, "Execute waypoint v3 failed due to action node child sum not equal next layer size. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_TREE_LAYER_NUM_TOO_MORE, "Execute waypoint v3 failed due to action tree layer num too more. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_TREE_LAYER_NUM_TOO_LESS, "Execute waypoint v3 failed due to action tree layer num too less. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_GROUP_NUM_OUT_OF_RANGE, "Execute waypoint v3 failed due to action group num out of range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_GROUP_VALID_RANGE_ERROR, "Execute waypoint v3 failed due to action group valid range error. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_TREE_ROOT_STATUS_INVALID, "Execute waypoint v3 failed due to action tree root status invalid. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_TREE_NODE_STATUS_INVALID, "Execute waypoint v3 failed due to action tree mode status invalid. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_BREAK_INFO_ACTION_GROUP_ID_OUT_OF_RANGE, "Execute waypoint v3 failed due to break info action group id out of range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_STATUS_TREE_SIZE_ERROR, "Execute waypoint v3 failed due to action status tree size error. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_BREAK_INFO_TRIGGER_RUN_RESULT_INVALID, "Execute waypoint v3 failed due to break info trigger run result invalid. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_BREAK_INFO_ACTION_GROUP_ID_REPEATED, "Execute waypoint v3 failed due to break info action group id repeated. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_BREAK_INFO_ACTION_LOCATION_REPEATED, "Execute waypoint v3 failed due to break info action location repeated. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_BREAK_INFO_ACTION_LOCATION_OUT_OF_RANGE, "Execute waypoint v3 failed due to break info action location out of range. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_RESUME_ID_NOT_IN_BREAK_INFO, "Execute waypoint v3 failed due to resume id not in break info. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_RESUME_INFO_MODIFY_ACTION_STATUS_FROM_NO_INTERRUPT_TO_INTERRUPT, "Execute waypoint v3 failed due to modify action status from no interrupt to interrupt. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_RESUME_FAIL_FOR_INVALID_RESUME_INFO, "Execute waypoint v3 failed due to action resume failed for invalid resume info. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTUATOR_COMMON_ACTUATOR_NOT_FOUND, "Execute waypoint v3 failed due to actuator not found. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRIGGER_NOT_FOUND, "Execute waypoint v3 failed due to trigger not found. ", NULL}, \
{DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRIGGER_SINGLE_TIME_CHECK_FAIL, "Execute waypoint v3 failed due to single time check failed. ", NULL}, \
#define DJI_RETURN_CODE_OK DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS /*!< Payload SDK return code represents as status is ok. */
#define DJI_RETURN_CODE_OK DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS /*!< Payload SDK return code represents as status is ok. */
#define DJI_RETURN_CODE_ERR_ALLOC DJI_ERROR_SYSTEM_MODULE_CODE_MEMORY_ALLOC_FAILED /*!< Payload SDK return code represents as status alloc error. */
#define DJI_RETURN_CODE_ERR_TIMEOUT DJI_ERROR_SYSTEM_MODULE_CODE_TIMEOUT /*!< Payload SDK return code represents as status timeout error. */
#define DJI_RETURN_CODE_ERR_NOT_FOUND DJI_ERROR_SYSTEM_MODULE_CODE_NOT_FOUND /*!< Payload SDK return code represents as status not found error. */
#define DJI_RETURN_CODE_ERR_OUT_OF_RANGE DJI_ERROR_SYSTEM_MODULE_CODE_OUT_OF_RANGE /*!< Payload SDK return code represents as status out of range error. */
#define DJI_RETURN_CODE_ERR_PARAM DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER /*!< Payload SDK return code represents as status parameter error. */
#define DJI_RETURN_CODE_ERR_SYSTEM DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR /*!< Payload SDK return code represents as status system error. */
#define DJI_RETURN_CODE_ERR_BUSY DJI_ERROR_SYSTEM_MODULE_CODE_BUSY /*!< Payload SDK return code represents as status busy error. */
#define DJI_RETURN_CODE_ERR_UNSUPPORT DJI_ERROR_SYSTEM_MODULE_CODE_NONSUPPORT /*!< Payload SDK return code represents as status nonsupport error. */
#define DJI_RETURN_CODE_ERR_UNKNOWN DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN /*!< Payload SDK return code represents as status unknown error. */
#define DJI_RETURN_CODE_ERR_TIMEOUT DJI_ERROR_SYSTEM_MODULE_CODE_TIMEOUT /*!< Payload SDK return code represents as status timeout error. */
#define DJI_RETURN_CODE_ERR_NOT_FOUND DJI_ERROR_SYSTEM_MODULE_CODE_NOT_FOUND /*!< Payload SDK return code represents as status not found error. */
#define DJI_RETURN_CODE_ERR_OUT_OF_RANGE DJI_ERROR_SYSTEM_MODULE_CODE_OUT_OF_RANGE /*!< Payload SDK return code represents as status out of range error. */
#define DJI_RETURN_CODE_ERR_PARAM DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER /*!< Payload SDK return code represents as status parameter error. */
#define DJI_RETURN_CODE_ERR_SYSTEM DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR /*!< Payload SDK return code represents as status system error. */
#define DJI_RETURN_CODE_ERR_BUSY DJI_ERROR_SYSTEM_MODULE_CODE_BUSY /*!< Payload SDK return code represents as status busy error. */
#define DJI_RETURN_CODE_ERR_UNSUPPORT DJI_ERROR_SYSTEM_MODULE_CODE_NONSUPPORT /*!< Payload SDK return code represents as status nonsupport error. */
#define DJI_RETURN_CODE_ERR_UNKNOWN DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN /*!< Payload SDK return code represents as status unknown error. */
/* Exported types ------------------------------------------------------------*/
/**
@ -375,6 +491,7 @@ typedef enum {
DJI_ERROR_MODULE_CAMERA_MANAGER,
DJI_ERROR_MODULE_GIMBAL_MANAGER,
DJI_ERROR_MODULE_WAYPOINT_V2,
DJI_ERROR_MODULE_WAYPOINT_V3,
DJI_ERROR_MODULE_ERROR,
} E_DjiErrorModule;
@ -391,6 +508,7 @@ typedef enum {
DJI_ERROR_SYSTEM_MODULE_RAW_CODE_INVALID_PARAMETER = 0x0E3,
DJI_ERROR_SYSTEM_MODULE_RAW_CODE_NONSUPPORT_IN_CURRENT_STATE = 0x0E4,
DJI_ERROR_SYSTEM_MODULE_RAW_CODE_SYSTEM_ERROR = 0x0EC,
DJI_ERROR_SYSTEM_MODULE_RAW_CODE_MODULE_INACTIVATED = 0xEE, /*!< Module is too not activated yet */
DJI_ERROR_SYSTEM_MODULE_RAW_CODE_HARDWARE_ERR = 0x0FA,
DJI_ERROR_SYSTEM_MODULE_RAW_CODE_INSUFFICIENT_ELECTRICITY = 0x0FB,
DJI_ERROR_SYSTEM_MODULE_RAW_CODE_UNKNOWN = 0x0FF,
@ -556,7 +674,6 @@ typedef enum {
DJI_ERROR_CAMERA_MANAGER_MODULE_RAW_CODE_SENSOR_ERROR = 0xEB, /*!< Sensor go wrong */
DJI_ERROR_CAMERA_MANAGER_MODULE_RAW_CODE_SYSTEM_ERROR = 0xEC, /*!< System error */
DJI_ERROR_CAMERA_MANAGER_MODULE_RAW_CODE_PARAMETER_TOTAL_TOO_LONG = 0xED, /*!< Length of the parameter is too long */
DJI_ERROR_CAMERA_MANAGER_MODULE_RAW_CODE_MODULE_INACTIVATED = 0xEE, /*!< Module is too not activated yet */
DJI_ERROR_CAMERA_MANAGER_MODULE_RAW_CODE_FIRMWARE_DATA_NUM_DISCONTINUOUS = 0xF0, /*!< Fireware data number is a discontinuous number */
DJI_ERROR_CAMERA_MANAGER_MODULE_RAW_CODE_FIRMWARE_VERIFICATION_ERROR = 0xF2, /*!< Error verifying fireware */
DJI_ERROR_CAMERA_MANAGER_MODULE_RAW_CODE_FLASH_WRITE_ERROR = 0xF4, /*!< Error writing flash */
@ -586,7 +703,6 @@ typedef enum {
DJI_ERROR_GIMBAL_MANAGER_MODULE_RAW_CODE_SENSOR_ERROR = 0xEB, /*!< Sensor go wrong */
DJI_ERROR_GIMBAL_MANAGER_MODULE_RAW_CODE_SYSTEM_ERROR = 0xEC, /*!< System error */
DJI_ERROR_GIMBAL_MANAGER_MODULE_RAW_CODE_PARAMETER_TOTAL_TOO_LONG = 0xED, /*!< Length of the parameter is too long */
DJI_ERROR_GIMBAL_MANAGER_MODULE_RAW_CODE_MODULE_INACTIVATED = 0xEE, /*!< Module is too not activated yet */
DJI_ERROR_GIMBAL_MANAGER_MODULE_RAW_CODE_FIRMWARE_DATA_NUM_DISCONTINUOUS = 0xF0, /*!< Fireware data number is a discontinuous number */
DJI_ERROR_GIMBAL_MANAGER_MODULE_RAW_CODE_FIRMWARE_VERIFICATION_ERROR = 0xF2, /*!< Error verifying fireware */
DJI_ERROR_GIMBAL_MANAGER_MODULE_RAW_CODE_FLASH_WRITE_ERROR = 0xF4, /*!< Error writing flash */
@ -737,6 +853,121 @@ typedef enum {
DJI_ERROR_WAYPOINT_V2_MODULE_RAW_CODE_ACTUATOR_PAYLOAD_EXEC_FAILED = 0x470002,
} E_DjiErrorWaypointV2ModuleRawCode;
typedef enum {
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_SUCCESS = 0x0000,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_MISSION_ID_NOT_EXIST = 1,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_WAYLINE_INFO_ERROR = 2,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_WPMZ_FILE_VERSION_NOT_MATCH = 3,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_WPMZ_FILE_LOAD_ERROR = 4,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_NO_BREAK_INFO = 5,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CMD_INVALID = 6,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_START_WAYLINE_WHEN_WAYLINE_RUNNING = 257,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_BREAK_WAYLINE_IN_CUR_STATE = 258,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_STOP_WAYLINE_WHEN_WAYLINE_NOT_RUNNING = 259,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_BREAK_WAYLINE_WHEN_WAYLINE_NOT_RUNNING = 260,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_REQUEST_DRONE_CONTROL = 261,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_RESUME_WAYLINE_IN_CUR_STATE = 262,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_HEIGHT_LIMIT = 513,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_RADIUS_LIMIT = 514,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CROSS_FLYLIMIT_AERA = 515,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_LOW_LIMIT = 516,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_OBSTACAL_STOP = 517,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_RTK_DISCONNECT = 518,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_BOUNDARY_LIMIT = 519,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_RC_PITCH_ROLL_BREAK = 520,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_AIRPORT_HEIGHT_LIMIT = 521,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_REQUEST_TAKEOFF_FAIL = 522,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_AUTOTAKEOFF_RUN_FAIL = 523,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_REQUEST_WAYLINE_FAIL = 524,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_AGRO_PLAN_FAIL = 525,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_REQUEST_QUICK_TAKEOFF_ASSIST_FAIL = 526,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_QUICK_TAKEOFF_ASSIST_RUN_FAIL = 527,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_VFENCE_LIMIT = 528,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_GPS_INVALID = 769,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_START_AT_CURRENT_RC_MODE = 770,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_HOME_POINT_NOT_RECORDED = 771,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_LOWER_BATTERY = 772,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_RETURN_HOME = 773,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ADSB_ERROR = 774,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_RC_LOST = 775,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_RTK_NOT_READY = 776,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_DRONE_IS_MOVING = 777,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_DRONE_ON_GROUND_MOTOR_ON = 778,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_SURFACE_FOLLOW_CAMERA_INVALID = 779,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_SURFACE_FOLLOW_HEIGHT_INVALID = 780,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_SURFACE_FOLLOW_MAP_WRONG = 781,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_HOMEPOINT_NOT_MATCH_RTK = 782,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_STRONG_WIND_GOHOME = 784,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_DRONE_CRITICAL_ERROR = 1023,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_FIND_PAYLOAD = 1025,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_EXECUTION_FAILED = 1026,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_FARM_NO_PESTICIDE = 1027,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_RADAR_DISCONNECT = 1028,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_USER_EXIT = 1281,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_USER_BREAK = 1282,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_USER_SET_GOHOME = 1283,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_USER_AGRO_PLANNER_STATE_CHANGE = 1284,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_USER_SWITCH_RC_MODE = 1285,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INIT_FAIL = 1536,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_JOB_EXIT_BUT_MIS_RUNNING = 1537,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_ON_GROUND_MOTOR_ON_CANNOT_GO = 1538,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_START_INDEX_OR_PROG = 1539,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_CSYS_MODE = 1540,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_HEIGHT_MODE = 1541,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_FLY_WP_MODE = 1542,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_YAW_MODE = 1543,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_TURN_DIR_MODE = 1544,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_WP_TYPE = 1545,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_FIR_LAS_WP_TYPE_ERROR = 1546,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_GLOB_VEL_OUT_OF_RANGE = 1547,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_WP_NUM_OUT_OF_RANGE = 1548,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_LAT_LONG_OUT_OF_RANGE = 1549,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_DAMP_DIS_OUT_OF_RANGE = 1550,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_MAX_VEL_OUT_OF_RANGE = 1551,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_VEL_OUT_OF_RANGE = 1552,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_WP_YAW_OUT_OF_RANGE = 1553,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_YAW_MODE_IN_VERT_SEGM = 1554,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_WP_BREAK_INFO_MISSION_ID_CHANGED = 1555,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_WP_BREAK_INFO_PROGRESS_OUT_OF_RANGE = 1556,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_WP_BREAK_INFO_INVALID_MISSION_STATE = 1557,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_WP_BREAK_INFO_WP_INDEX_OUT_OF_RANGE = 1558,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_BREAK_LAT_LONG_OUT_OF_RANGE = 1559,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_BREAK_INFO_WP_YAW_OUT_OF_RANGE = 1560,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_BREAK_INFO_FLAG = 1561,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_GET_TRAJ_INFO_FAILED = 1562,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_GENERATE_FAIL = 1563,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_LIB_RUN_FAIL = 1564,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_LIB_EMERGENCY_BRAKE = 1565,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_NOT_FOUND = 1588,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_INDEX_REPEATED = 1591,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_INFO_SIZE_TOO_LONG_OR_TOO_SHORT = 1592,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_TREE_EMPTY = 1593,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_TREE_LAYER_EMPTY = 1594,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_ID_REPEATED = 1595,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_NODE_CHILDREN_NUM_LT_2 = 1596,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_INDEX_OUT_OF_RANGE = 1597,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_ID_IS_65535 = 1598,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_NODE_CHILDNUM_SUM_NOT_EQ_NEXT_LAYER_SIZE = 1599,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_TREE_LAYER_NUM_TOO_MORE = 1600,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_TREE_LAYER_NUM_TOO_LESS = 1601,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_GROUP_NUM_OUT_OF_RANGE = 1602,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_GROUP_VALID_RANGE_ERROR = 1603,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_TREE_ROOT_STATUS_INVALID = 1604,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_TREE_NODE_STATUS_INVALID = 1605,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_BREAK_INFO_ACTION_GROUP_ID_OUT_OF_RANGE = 1606,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_STATUS_TREE_SIZE_ERROR = 1607,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_BREAK_INFO_TRIGGER_RUN_RESULT_INVALID = 1608,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_BREAK_INFO_ACTION_GROUP_ID_REPEATED = 1609,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_BREAK_INFO_ACTION_LOCATION_REPEATED = 1610,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_BREAK_INFO_ACTION_LOCATION_OUT_OF_RANGE = 1611,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_RESUME_ID_NOT_IN_BREAK_INFO = 1612,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_RESUME_INFO_MODIFY_ACTION_STATUS_FROM_NO_INTERRUPT_TO_INTERRUPT = 1613,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_RESUME_FAIL_FOR_INVALID_RESUME_INFO = 1614,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTUATOR_COMMON_ACTUATOR_NOT_FOUND = 1634,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRIGGER_NOT_FOUND = 1649,
DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRIGGER_SINGLE_TIME_CHECK_FAIL = 1650,
} E_DjiErrorWaypoint3ModuleRawCode;
//@formatter:off
/**
* @brief DJI error code complete works. Users can search all error messages here.
@ -870,7 +1101,7 @@ enum DjiErrorCode {
DJI_ERROR_CAMERA_MANAGER_MODULE_CODE_SENSOR_ERROR = DJI_ERROR_CODE(DJI_ERROR_MODULE_CAMERA_MANAGER, DJI_ERROR_CAMERA_MANAGER_MODULE_RAW_CODE_SENSOR_ERROR),
DJI_ERROR_CAMERA_MANAGER_MODULE_CODE_SYSTEM_ERROR = DJI_ERROR_CODE(DJI_ERROR_MODULE_CAMERA_MANAGER, DJI_ERROR_CAMERA_MANAGER_MODULE_RAW_CODE_SYSTEM_ERROR),
DJI_ERROR_CAMERA_MANAGER_MODULE_CODE_PARAMETER_TOTAL_TOO_LONG = DJI_ERROR_CODE(DJI_ERROR_MODULE_CAMERA_MANAGER, DJI_ERROR_CAMERA_MANAGER_MODULE_RAW_CODE_PARAMETER_TOTAL_TOO_LONG),
DJI_ERROR_CAMERA_MANAGER_MODULE_CODE_MODULE_INACTIVATED = DJI_ERROR_CODE(DJI_ERROR_MODULE_CAMERA_MANAGER, DJI_ERROR_CAMERA_MANAGER_MODULE_RAW_CODE_MODULE_INACTIVATED),
DJI_ERROR_CAMERA_MANAGER_MODULE_CODE_MODULE_INACTIVATED = DJI_ERROR_CODE(DJI_ERROR_MODULE_CAMERA_MANAGER, DJI_ERROR_SYSTEM_MODULE_RAW_CODE_MODULE_INACTIVATED),
DJI_ERROR_CAMERA_MANAGER_MODULE_CODE_FIRMWARE_DATA_NUM_DISCONTINUOUS = DJI_ERROR_CODE(DJI_ERROR_MODULE_CAMERA_MANAGER, DJI_ERROR_CAMERA_MANAGER_MODULE_RAW_CODE_FIRMWARE_DATA_NUM_DISCONTINUOUS),
DJI_ERROR_CAMERA_MANAGER_MODULE_CODE_FIRMWARE_VERIFICATION_ERROR = DJI_ERROR_CODE(DJI_ERROR_MODULE_CAMERA_MANAGER, DJI_ERROR_CAMERA_MANAGER_MODULE_RAW_CODE_FIRMWARE_VERIFICATION_ERROR),
DJI_ERROR_CAMERA_MANAGER_MODULE_CODE_FLASH_WRITE_ERROR = DJI_ERROR_CODE(DJI_ERROR_MODULE_CAMERA_MANAGER, DJI_ERROR_CAMERA_MANAGER_MODULE_RAW_CODE_FLASH_WRITE_ERROR),
@ -896,7 +1127,7 @@ enum DjiErrorCode {
DJI_ERROR_GIMBAL_MANAGER_MODULE_CODE_SENSOR_ERROR = DJI_ERROR_CODE(DJI_ERROR_MODULE_GIMBAL_MANAGER, DJI_ERROR_GIMBAL_MANAGER_MODULE_RAW_CODE_SENSOR_ERROR),
DJI_ERROR_GIMBAL_MANAGER_MODULE_CODE_SYSTEM_ERROR = DJI_ERROR_CODE(DJI_ERROR_MODULE_GIMBAL_MANAGER, DJI_ERROR_GIMBAL_MANAGER_MODULE_RAW_CODE_SYSTEM_ERROR),
DJI_ERROR_GIMBAL_MANAGER_MODULE_CODE_PARAMETER_TOTAL_TOO_LONG = DJI_ERROR_CODE(DJI_ERROR_MODULE_GIMBAL_MANAGER, DJI_ERROR_GIMBAL_MANAGER_MODULE_RAW_CODE_PARAMETER_TOTAL_TOO_LONG),
DJI_ERROR_GIMBAL_MANAGER_MODULE_CODE_MODULE_INACTIVATED = DJI_ERROR_CODE(DJI_ERROR_MODULE_GIMBAL_MANAGER, DJI_ERROR_GIMBAL_MANAGER_MODULE_RAW_CODE_MODULE_INACTIVATED),
DJI_ERROR_GIMBAL_MANAGER_MODULE_CODE_MODULE_INACTIVATED = DJI_ERROR_CODE(DJI_ERROR_MODULE_GIMBAL_MANAGER, DJI_ERROR_SYSTEM_MODULE_RAW_CODE_MODULE_INACTIVATED),
DJI_ERROR_GIMBAL_MANAGER_MODULE_CODE_FIRMWARE_DATA_NUM_DISCONTINUOUS = DJI_ERROR_CODE(DJI_ERROR_MODULE_GIMBAL_MANAGER, DJI_ERROR_GIMBAL_MANAGER_MODULE_RAW_CODE_FIRMWARE_DATA_NUM_DISCONTINUOUS),
DJI_ERROR_GIMBAL_MANAGER_MODULE_CODE_FIRMWARE_VERIFICATION_ERROR = DJI_ERROR_CODE(DJI_ERROR_MODULE_GIMBAL_MANAGER, DJI_ERROR_GIMBAL_MANAGER_MODULE_RAW_CODE_FIRMWARE_VERIFICATION_ERROR),
DJI_ERROR_GIMBAL_MANAGER_MODULE_CODE_FLASH_WRITE_ERROR = DJI_ERROR_CODE(DJI_ERROR_MODULE_GIMBAL_MANAGER, DJI_ERROR_GIMBAL_MANAGER_MODULE_RAW_CODE_FLASH_WRITE_ERROR),
@ -1016,6 +1247,120 @@ enum DjiErrorCode {
DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_PAYLOAD_RESV = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V2, DJI_ERROR_WAYPOINT_V2_MODULE_RAW_CODE_ACTUATOR_PAYLOAD_RESV),
DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_PAYLOAD_FAIL_TO_SEND_CMD_TO_PAYLOAD = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V2, DJI_ERROR_WAYPOINT_V2_MODULE_RAW_CODE_ACTUATOR_PAYLOAD_FAIL_TO_SEND_CMD_TO_PAYLOAD),
DJI_ERROR_WAYPOINT_V2_MODULE_CODE_ACTUATOR_PAYLOAD_EXEC_FAILED = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V2, DJI_ERROR_WAYPOINT_V2_MODULE_RAW_CODE_ACTUATOR_PAYLOAD_EXEC_FAILED),
/* Waypoint v3 total errors */
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_COMMON_SUCCESS = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_SUCCESS),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_MISSION_ID_NOT_EXIST = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_MISSION_ID_NOT_EXIST),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_WAYLINE_INFO_ERROR = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_WAYLINE_INFO_ERROR),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_WPMZ_FILE_VERSION_NOT_MATCH = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_WPMZ_FILE_VERSION_NOT_MATCH),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_WPMZ_FILE_LOAD_ERROR = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_WPMZ_FILE_LOAD_ERROR),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_NO_BREAK_INFO = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_NO_BREAK_INFO),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CMD_INVALID = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CMD_INVALID),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_START_WAYLINE_WHEN_WAYLINE_RUNNING = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_START_WAYLINE_WHEN_WAYLINE_RUNNING),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_BREAK_WAYLINE_IN_CUR_STATE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_BREAK_WAYLINE_IN_CUR_STATE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_STOP_WAYLINE_WHEN_WAYLINE_NOT_RUNNING = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_STOP_WAYLINE_WHEN_WAYLINE_NOT_RUNNING),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_BREAK_WAYLINE_WHEN_WAYLINE_NOT_RUNNING = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_BREAK_WAYLINE_WHEN_WAYLINE_NOT_RUNNING),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_REQUEST_DRONE_CONTROL = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_REQUEST_DRONE_CONTROL),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_RESUME_WAYLINE_IN_CUR_STATE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_RESUME_WAYLINE_IN_CUR_STATE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_HEIGHT_LIMIT = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_HEIGHT_LIMIT),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_RADIUS_LIMIT = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_RADIUS_LIMIT),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CROSS_FLYLIMIT_AERA = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CROSS_FLYLIMIT_AERA),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_LOW_LIMIT = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_LOW_LIMIT),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_OBSTACAL_STOP = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_OBSTACAL_STOP),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_RTK_DISCONNECT = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_RTK_DISCONNECT),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_BOUNDARY_LIMIT = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_BOUNDARY_LIMIT),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_RC_PITCH_ROLL_BREAK = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_RC_PITCH_ROLL_BREAK),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_AIRPORT_HEIGHT_LIMIT = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_AIRPORT_HEIGHT_LIMIT),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_REQUEST_TAKEOFF_FAIL = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_REQUEST_TAKEOFF_FAIL),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_AUTOTAKEOFF_RUN_FAIL = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_AUTOTAKEOFF_RUN_FAIL),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_REQUEST_WAYLINE_FAIL = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_REQUEST_WAYLINE_FAIL),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_AGRO_PLAN_FAIL = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_AGRO_PLAN_FAIL),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_REQUEST_QUICK_TAKEOFF_ASSIST_FAIL = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_REQUEST_QUICK_TAKEOFF_ASSIST_FAIL),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_QUICK_TAKEOFF_ASSIST_RUN_FAIL = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_QUICK_TAKEOFF_ASSIST_RUN_FAIL),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_VFENCE_LIMIT = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_VFENCE_LIMIT),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_GPS_INVALID = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_GPS_INVALID),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_START_AT_CURRENT_RC_MODE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_START_AT_CURRENT_RC_MODE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_HOME_POINT_NOT_RECORDED = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_HOME_POINT_NOT_RECORDED),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_LOWER_BATTERY = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_LOWER_BATTERY),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_RETURN_HOME = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_RETURN_HOME),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ADSB_ERROR = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ADSB_ERROR),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_RC_LOST = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_RC_LOST),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_RTK_NOT_READY = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_RTK_NOT_READY),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_DRONE_IS_MOVING = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_DRONE_IS_MOVING),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_DRONE_ON_GROUND_MOTOR_ON = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_DRONE_ON_GROUND_MOTOR_ON),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_SURFACE_FOLLOW_CAMERA_INVALID = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_SURFACE_FOLLOW_CAMERA_INVALID),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_SURFACE_FOLLOW_HEIGHT_INVALID = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_SURFACE_FOLLOW_HEIGHT_INVALID),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_SURFACE_FOLLOW_MAP_WRONG = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_SURFACE_FOLLOW_MAP_WRONG),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_HOMEPOINT_NOT_MATCH_RTK = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_HOMEPOINT_NOT_MATCH_RTK),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_STRONG_WIND_GOHOME = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_STRONG_WIND_GOHOME),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_DRONE_CRITICAL_ERROR = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_DRONE_CRITICAL_ERROR),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_CANNOT_FIND_PAYLOAD = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_CANNOT_FIND_PAYLOAD),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_EXECUTION_FAILED = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_EXECUTION_FAILED),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_FARM_NO_PESTICIDE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_FARM_NO_PESTICIDE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_RADAR_DISCONNECT = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_RADAR_DISCONNECT),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_USER_EXIT = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_USER_EXIT),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_USER_BREAK = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_USER_BREAK),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_USER_SET_GOHOME = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_USER_SET_GOHOME),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_USER_AGRO_PLANNER_STATE_CHANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_USER_AGRO_PLANNER_STATE_CHANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_USER_SWITCH_RC_MODE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_USER_SWITCH_RC_MODE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INIT_FAIL = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INIT_FAIL),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_JOB_EXIT_BUT_MIS_RUNNING = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_JOB_EXIT_BUT_MIS_RUNNING),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_ON_GROUND_MOTOR_ON_CANNOT_GO = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_ON_GROUND_MOTOR_ON_CANNOT_GO),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_START_INDEX_OR_PROG = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_START_INDEX_OR_PROG),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_CSYS_MODE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_CSYS_MODE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_HEIGHT_MODE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_HEIGHT_MODE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_FLY_WP_MODE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_FLY_WP_MODE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_YAW_MODE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_YAW_MODE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_TURN_DIR_MODE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_TURN_DIR_MODE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_WP_TYPE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_WP_TYPE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_FIR_LAS_WP_TYPE_ERROR = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_FIR_LAS_WP_TYPE_ERROR),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_GLOB_VEL_OUT_OF_RANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_GLOB_VEL_OUT_OF_RANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_WP_NUM_OUT_OF_RANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_WP_NUM_OUT_OF_RANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_LAT_LONG_OUT_OF_RANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_LAT_LONG_OUT_OF_RANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_DAMP_DIS_OUT_OF_RANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_DAMP_DIS_OUT_OF_RANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_MAX_VEL_OUT_OF_RANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_MAX_VEL_OUT_OF_RANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_VEL_OUT_OF_RANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_VEL_OUT_OF_RANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_WP_YAW_OUT_OF_RANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_WP_YAW_OUT_OF_RANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_YAW_MODE_IN_VERT_SEGM = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_YAW_MODE_IN_VERT_SEGM),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_WP_BREAK_INFO_MISSION_ID_CHANGED = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_WP_BREAK_INFO_MISSION_ID_CHANGED),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_WP_BREAK_INFO_PROGRESS_OUT_OF_RANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_WP_BREAK_INFO_PROGRESS_OUT_OF_RANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_WP_BREAK_INFO_INVALID_MISSION_STATE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_WP_BREAK_INFO_INVALID_MISSION_STATE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_WP_BREAK_INFO_WP_INDEX_OUT_OF_RANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_WP_BREAK_INFO_WP_INDEX_OUT_OF_RANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_BREAK_LAT_LONG_OUT_OF_RANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_BREAK_LAT_LONG_OUT_OF_RANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_BREAK_INFO_WP_YAW_OUT_OF_RANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_BREAK_INFO_WP_YAW_OUT_OF_RANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_INVALID_BREAK_INFO_FLAG = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_INVALID_BREAK_INFO_FLAG),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_GET_TRAJ_INFO_FAILED = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_GET_TRAJ_INFO_FAILED),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_GENERATE_FAIL = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_GENERATE_FAIL),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_LIB_RUN_FAIL = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_LIB_RUN_FAIL),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRAJ_LIB_EMERGENCY_BRAKE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRAJ_LIB_EMERGENCY_BRAKE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_NOT_FOUND = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_NOT_FOUND),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_INDEX_REPEATED = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_INDEX_REPEATED),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_INFO_SIZE_TOO_LONG_OR_TOO_SHORT = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_INFO_SIZE_TOO_LONG_OR_TOO_SHORT),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_TREE_EMPTY = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_TREE_EMPTY),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_TREE_LAYER_EMPTY = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_TREE_LAYER_EMPTY),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_ID_REPEATED = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_ID_REPEATED),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_NODE_CHILDREN_NUM_LT_2 = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_NODE_CHILDREN_NUM_LT_2),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_INDEX_OUT_OF_RANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_INDEX_OUT_OF_RANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_ID_IS_65535 = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_ID_IS_65535),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_NODE_CHILDNUM_SUM_NOT_EQ_NEXT_LAYER_SIZE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_NODE_CHILDNUM_SUM_NOT_EQ_NEXT_LAYER_SIZE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_TREE_LAYER_NUM_TOO_MORE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_TREE_LAYER_NUM_TOO_MORE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_TREE_LAYER_NUM_TOO_LESS = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_TREE_LAYER_NUM_TOO_LESS),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_GROUP_NUM_OUT_OF_RANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_GROUP_NUM_OUT_OF_RANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_GROUP_VALID_RANGE_ERROR = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_GROUP_VALID_RANGE_ERROR),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_TREE_ROOT_STATUS_INVALID = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_TREE_ROOT_STATUS_INVALID),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_TREE_NODE_STATUS_INVALID = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_TREE_NODE_STATUS_INVALID),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_BREAK_INFO_ACTION_GROUP_ID_OUT_OF_RANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_BREAK_INFO_ACTION_GROUP_ID_OUT_OF_RANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_STATUS_TREE_SIZE_ERROR = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_STATUS_TREE_SIZE_ERROR),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_BREAK_INFO_TRIGGER_RUN_RESULT_INVALID = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_BREAK_INFO_TRIGGER_RUN_RESULT_INVALID),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_BREAK_INFO_ACTION_GROUP_ID_REPEATED = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_BREAK_INFO_ACTION_GROUP_ID_REPEATED),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_BREAK_INFO_ACTION_LOCATION_REPEATED = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_BREAK_INFO_ACTION_LOCATION_REPEATED),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_BREAK_INFO_ACTION_LOCATION_OUT_OF_RANGE = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_BREAK_INFO_ACTION_LOCATION_OUT_OF_RANGE),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_RESUME_ID_NOT_IN_BREAK_INFO = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_RESUME_ID_NOT_IN_BREAK_INFO),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_RESUME_INFO_MODIFY_ACTION_STATUS_FROM_NO_INTERRUPT_TO_INTERRUPT = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_RESUME_INFO_MODIFY_ACTION_STATUS_FROM_NO_INTERRUPT_TO_INTERRUPT),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTION_COMMON_ACTION_RESUME_FAIL_FOR_INVALID_RESUME_INFO = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTION_COMMON_ACTION_RESUME_FAIL_FOR_INVALID_RESUME_INFO),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_ACTUATOR_COMMON_ACTUATOR_NOT_FOUND = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_ACTUATOR_COMMON_ACTUATOR_NOT_FOUND),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRIGGER_NOT_FOUND = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRIGGER_NOT_FOUND),
DJI_ERROR_WAYPOINT_V3_MODULE_CODE_TRIGGER_SINGLE_TIME_CHECK_FAIL = DJI_ERROR_CODE(DJI_ERROR_MODULE_WAYPOINT_V3, DJI_ERROR_WAYPOINT_V3_MODULE_RAW_CODE_TRIGGER_SINGLE_TIME_CHECK_FAIL),
};
//@formatter:on

View File

@ -520,6 +520,12 @@ typedef enum {
DJI_FC_SUBSCRIPTION_TOPIC_BATTERY_SINGLE_INFO_INDEX2 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC,
47),
/*!
* @brief Please refer to ::T_DjiFcSubscriptionImuAttiNaviDataWithTimestamp for information about data structure.
* @datastruct \ref T_DjiFcSubscriptionImuAttiNaviDataWithTimestamp
*/
DJI_FC_SUBSCRIPTION_TOPIC_IMU_ATTI_NAVI_DATA_WITH_TIMESTAMP = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 48),
/*! Total number of topics that can be subscribed. */
DJI_FC_SUBSCRIPTION_TOPIC_TOTAL_NUMBER,
} E_DjiFcSubscriptionTopic;
@ -723,6 +729,64 @@ typedef enum {
DJI_FC_SUBSCRIPTION_BATTERY_SOC_INVALID = 4, /*!< Battery SOC state is invalid. */
} E_DJIFcSubscriptionBatterySocState;
/**
* @brief Flight control mode.
*/
typedef enum {
DJI_FC_SUBSCRIPTION_CONTROL_MODE_UNKNOWN = 0,
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_ANG_VER_VEL_YAW_ANG = 1, /*!< Horizontal mode is angle, vertical mode is velocity, yaw mode is angle. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_ANG_VER_VEL_YAW_RAT = 2, /*!< Horizontal mode is angle, vertical mode is velocity, yaw mode is rate. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_VEL_VER_VEL_YAW_ANG = 3, /*!< Horizontal mode is velocity, vertical mode is velocity, yaw mode is angle. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_VEL_VER_VEL_YAW_RAT = 4, /*!< Horizontal mode is velocity, vertical mode is velocity, yaw mode is rate. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_POS_VER_VEL_YAW_ANG = 5, /*!< Horizontal mode is position, vertical mode is velocity, yaw mode is angle. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_POS_VER_VEL_YAW_RAT = 6, /*!< Horizontal mode is position, vertical mode is velocity, yaw mode is rate. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_ANG_VER_POS_YAW_ANG = 7, /*!< Horizontal mode is angle, vertical mode is position, yaw mode is angle. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_ANG_VER_POS_YAW_RAT = 8, /*!< Horizontal mode is angle, vertical mode is position, yaw mode is rate. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_VEL_VER_POS_YAW_ANG = 9, /*!< Horizontal mode is velocity, vertical mode is position, yaw mode is angle. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_VEL_VER_POS_YAW_RAT = 10, /*!< Horizontal mode is velocity, vertical mode is position, yaw mode is rate. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_POS_VER_POS_YAW_ANG = 11, /*!< Horizontal mode is position, vertical mode is position, yaw mode is angle. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_POS_VER_POS_YAW_RAT = 12, /*!< Horizontal mode is position, vertical mode is position, yaw mode is rate. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_ANG_VER_THR_YAW_ANG = 13, /*!< Horizontal mode is angle, vertical mode is thrust, yaw mode is angle. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_ANG_VER_THR_YAW_RAT = 14, /*!< Horizontal mode is angle, vertical mode is thrust, yaw mode is rate. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_VEL_VER_THR_YAW_ANG = 15, /*!< Horizontal mode is velocity, vertical mode is thrust, yaw mode is angle. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_VEL_VER_THR_YAW_RAT = 16, /*!< Horizontal mode is velocity, vertical mode is thrust, yaw mode is rate. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_POS_VER_THR_YAW_ANG = 17, /*!< Horizontal mode is position, vertical mode is thrust, yaw mode is angle. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_POS_VER_THR_YAW_RAT = 18, /*!< Horizontal mode is position, vertical mode is thrust, yaw mode is rate. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_AEL_VER_VEL_YAW_RAT = 19, /*!< Horizontal mode is angle-rate, vertical mode is velocity, yaw mode is rate. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_AEL_VER_POS_YAW_RAT = 20, /*!< Horizontal mode is angle-rate, vertical mode is thrust, yaw mode is rate. */
DJI_FC_SUBSCRIPTION_CONTROL_MODE_HOR_AEL_VER_THR_YAW_RAT = 21, /*!< Horizontal mode is angle-rate, vertical mode is velocity, yaw mode is rate. */
} E_DJIFcSubscriptionControlMode;
/**
* @brief Flight control authority.
*/
typedef enum {
DJI_FC_SUBSCRIPTION_CONTROL_AUTHORITY_RC = 0, /*!< Authority is in remote control */
DJI_FC_SUBSCRIPTION_CONTROL_AUTHORITY_MSDK = 1, /*!< Authority is in MSDK */
DJI_FC_SUBSCRIPTION_CONTROL_AUTHORITY_PSDK = 4, /*!< Authority is in PSDK */
DJI_FC_SUBSCRIPTION_CONTROL_AUTHORITY_DOCK = 5, /*!< Authority is in dock */
} E_DJIFcSubscriptionControlAuthority;
/**
* @brief Flight control authority change reason.
*/
typedef enum {
DJI_FC_SUBSCRIPTION_AUTHORITY_CHANGE_REASON_UNKNOWN = 0, /*!< Reason unknown */
DJI_FC_SUBSCRIPTION_AUTHORITY_CHANGE_REASON_MSDK_REQUEST = 1, /*!< Contro authority changed by MSDK request. */
DJI_FC_SUBSCRIPTION_AUTHORITY_CHANGE_REASON_USER_REQUEST = 2, /*!< Contro authority changed by user request. */
DJI_FC_SUBSCRIPTION_AUTHORITY_CHANGE_REASON_PSDK_REQUEST = 3, /*!< Contro authority changed by PSDK request. */
DJI_FC_SUBSCRIPTION_AUTHORITY_CHANGE_REASON_RC_LOST = 4, /*!< Contro authority changed for remote control lost. */
DJI_FC_SUBSCRIPTION_AUTHORITY_CHANGE_REASON_RC_NOT_P_MODE = 5, /*!< Contro authority changed for remote control not in P mode. */
DJI_FC_SUBSCRIPTION_AUTHORITY_CHANGE_REASON_RC_SWITCH = 6, /*!< Contro authority changed for remote control switching mode. */
DJI_FC_SUBSCRIPTION_AUTHORITY_CHANGE_REASON_RC_PAUSE_STOP = 7, /*!< Contro authority changed for remote control stop key paused. */
DJI_FC_SUBSCRIPTION_AUTHORITY_CHANGE_REASON_RC_ONE_KEY_GO_HOME = 8, /*!< Contro authority changed for remote control go-home key paused. */
DJI_FC_SUBSCRIPTION_AUTHORITY_CHANGE_REASON_BATTERY_LOW_GO_HOME = 9, /*!< Contro authority changed for remote control go-home key paused. */
DJI_FC_SUBSCRIPTION_AUTHORITY_CHANGE_REASON_BATTERY_SUPER_LOW_LANDING = 10, /*!< Contro authority changed for going home caused by low batter power. */
DJI_FC_SUBSCRIPTION_AUTHORITY_CHANGE_REASON_PSDK_LOST = 11, /*!< Contro authority changed for PSDK lost. */
DJI_FC_SUBSCRIPTION_AUTHORITY_CHANGE_REASON_NEAR_BOUNDARY = 13, /*!< Contro authority changed for nearing boundary. */
DJI_FC_SUBSCRIPTION_AUTHORITY_CHANGE_REASON_AIRPORT_REQUEST = 14, /*!< Contro authority changed by airport request. */
} E_DJIFcSubscriptionAuthorityChangeReason;
#pragma pack(1)
/**
@ -994,11 +1058,22 @@ typedef struct BatterySingleInfo {
* @brief struct for TOPIC_CONTROL_DEVICE and data broadcast, return SDK info
*/
typedef struct SDKCtrlInfo {
uint8_t controlMode; /*!< See CtlrMode in dji_status.hpp*/
uint8_t deviceStatus: 3; /*!< 0->rc 1->app 4->serial */
uint8_t flightStatus: 1; /*!< 1->opensd 0->close */
uint8_t vrcStatus: 1;
uint8_t reserved: 3;
union {
/* Used by M300 & M350 */
struct {
uint8_t controlMode; /*!< enum-type: E_DJIFcSubscriptionControlMode. */
uint8_t deviceStatus: 3; /*!< 0->rc 1->app 4->psdk */
uint8_t flightStatus: 1; /*!< 1->open 0->closed */
uint8_t vrcStatus: 1;
uint8_t reserved: 3;
};
/* Used by other aircrafts */
struct {
uint8_t controlAuthority; /*!< enum-type: E_DJIFcSubscriptionControlAuthority. */
uint8_t controlAuthorityChangeReason; /*!< enum-type: E_DJIFcSubscriptionAuthorityChangeReason. */
};
};
} T_DjiFcSubscriptionControlDevice; // pack(1)
/*!
@ -1165,6 +1240,27 @@ typedef struct GimbalThreeData {
GimbalAnglesData anglesData[3];
} T_DjiFcSubscriptionThreeGimbalData;
/**
* @brief Struct for the topic DJI_FC_SUBSCRIPTION_TOPIC_IMU_ATTI_NAVI_DATA_WITH_TIMESTAMP. Used in M300
*/
typedef struct ImuAttiNaviDataWithTimestamp {
uint16_t version;
uint16_t flag;
dji_f32_t pn_x;
dji_f32_t pn_y;
dji_f32_t pn_z;
dji_f32_t vn_x;
dji_f32_t vn_y;
dji_f32_t vn_z;
dji_f32_t an_x;
dji_f32_t an_y;
dji_f32_t an_z;
dji_f32_t q[4];
uint16_t resv;
uint16_t cnt;
uint32_t timestamp;
} T_DjiFcSubscriptionImuAttiNaviDataWithTimestamp;
#pragma pack()
/* Exported functions --------------------------------------------------------*/

View File

@ -41,100 +41,106 @@ extern "C" {
typedef uint16_t E_DjiFlightControllerGoHomeAltitude; /*!< Unit:meter, range 20~500 */
/**
* @brief The UAV's actions when rc is lost.
* @brief The aircraft's actions when RC is lost.
*/
typedef enum {
DJI_FLIGHT_CONTROLLER_RC_LOST_ACTION_HOVER = 0, /*!< Aircraft will execute hover cation when rc is lost. */
DJI_FLIGHT_CONTROLLER_RC_LOST_ACTION_LANDING = 1, /*!< Aircraft will execute land cation when rc is lost. */
DJI_FLIGHT_CONTROLLER_RC_LOST_ACTION_GOHOME = 2, /*!< Aircraft will execute go-home cation when rc is lost. */
DJI_FLIGHT_CONTROLLER_RC_LOST_ACTION_HOVER = 0, /*!< Aircraft will execute hover action when RC is lost. */
DJI_FLIGHT_CONTROLLER_RC_LOST_ACTION_LANDING = 1, /*!< Aircraft will execute land action when RC is lost. */
DJI_FLIGHT_CONTROLLER_RC_LOST_ACTION_GOHOME = 2, /*!< Aircraft will execute go-home action when RC is lost. */
} E_DjiFlightControllerRCLostAction;
/**
* @brief Enable/Disable RTK position enum
*/
typedef enum {
DJI_FLIGHT_CONTROLLER_DISABLE_RTK_POSITION = 0, /*!< 0: The UAV will use GPS data instead of RTK data to execute
* actions which require location information(waypointgo home...)
DJI_FLIGHT_CONTROLLER_DISABLE_RTK_POSITION = 0, /*!< 0: The aircraft will use GPS data instead of RTK data to execute
* actions which requires location information(waypoint, go home...)
*/
DJI_FLIGHT_CONTROLLER_ENABLE_RTK_POSITION = 1, /*!< 1:The UAV will use RTK data instead of GPS data to execute
* actions which require location information(waypointgo home...)*/
DJI_FLIGHT_CONTROLLER_ENABLE_RTK_POSITION = 1, /*!< 1:The aircraft will use RTK data instead of GPS data to execute
* actions which requires location information(waypoint, go home...)*/
} E_DjiFlightControllerRtkPositionEnableStatus;
/**
* @brief Enable/Disable obstacle avoidance enum
* @brief Enable/Disable obstacle sensing enum
*/
typedef enum {
DJI_FLIGHT_CONTROLLER_DISABLE_OBSTACLE_AVOIDANCE = 0, /*!< 0: The UAV will not perform obstacle avoidance in
DJI_FLIGHT_CONTROLLER_DISABLE_OBSTACLE_AVOIDANCE = 0, /*!< 0: The aircraft will not perform obstacle sensing in
* the specified direction */
DJI_FLIGHT_CONTROLLER_ENABLE_OBSTACLE_AVOIDANCE = 1, /*!< 0: The UAV will perform obstacle avoidance in the
DJI_FLIGHT_CONTROLLER_ENABLE_OBSTACLE_AVOIDANCE = 1, /*!< 0: The aircraft will perform obstacle sensing in the
* specified direction */
} E_DjiFlightControllerObstacleAvoidanceEnableStatus;
/**
* @brief Enable/Disable emergency stop motor function enum
* @note Attention:Enable emergency-stop-motor function is very dangerous in the air.it will make the aircraft crash!!!
* @note Enable emergency-stop-motor function is very dangerous in the air. It will make the aircraft crash!!!
*/
typedef enum {
DJI_FLIGHT_CONTROLLER_ENABLE_EMERGENCY_STOP_MOTOR = 0x01, /*!< Execute emergency-stop-motor action */
} E_DjiFlightControllerEmergencyStopMotor;
/**
* @brief Obtain/Release joystick control authority command enum
* @note You have obtain joystick control authority successfully before using joystick.
* @brief Obtain/Release joystick control permission command enum
* @note You have obtained joystick control permission successfully before using joystick.
*/
typedef enum {
DJI_FLIGHT_CONTROLLER_RELEASE_JOYSTICK_CTRL_AUTHORITY = 0, /*!< Obtain joystick authority */
DJI_FLIGHT_CONTROLLER_OBTAIN_JOYSTICK_CTRL_AUTHORITY = 1, /*!< Release joystick authority */
DJI_FLIGHT_CONTROLLER_RELEASE_JOYSTICK_CTRL_AUTHORITY = 0, /*!< Obtain joystick permission */
DJI_FLIGHT_CONTROLLER_OBTAIN_JOYSTICK_CTRL_AUTHORITY = 1, /*!< Release joystick permission */
} E_DjiFlightControllerJoystickCtrlAuthorityAction;
/**
* @brief The UAV's joystick control authority owner enum
* @brief The aircraft's joystick control permission owner enum
*/
typedef enum {
DJI_FLIGHT_CONTROLLER_JOYSTICK_CTRL_AUTHORITY_RC = 0, /*!< Rc could control UAV with joystick. */
DJI_FLIGHT_CONTROLLER_JOYSTICK_CTRL_AUTHORITY_MSDK = 1, /*!< MSDK could control UAV with joystick. */
DJI_FLIGHT_CONTROLLER_JOYSTICK_CTRL_AUTHORITY_INTERNAL = 2, /*!< Special Internal modules could control UAV
DJI_FLIGHT_CONTROLLER_JOYSTICK_CTRL_AUTHORITY_RC = 0, /*!< RC could control aircraft with joystick. */
DJI_FLIGHT_CONTROLLER_JOYSTICK_CTRL_AUTHORITY_MSDK = 1, /*!< MSDK could control aircraft with joystick. */
DJI_FLIGHT_CONTROLLER_JOYSTICK_CTRL_AUTHORITY_INTERNAL = 2, /*!< Special Internal modules could control aircraft
* with joystick. */
DJI_FLIGHT_CONTROLLER_JOYSTICK_CTRL_AUTHORITY_OSDK = 4, /*!< OSDK could control UAV with joystick. */
DJI_FLIGHT_CONTROLLER_JOYSTICK_CTRL_AUTHORITY_OSDK = 4, /*!< PSDK could control aircraft with joystick. */
} E_DjiFlightControllerJoystickCtrlAuthority;
/**
* @brief The UAV's joystick control authority switch reason enum
* @brief The aircraft's joystick control permission switch reason enum
*/
typedef enum {
DJI_FLIGHT_CONTROLLER_MSDK_GET_JOYSTICK_CTRL_AUTH_EVENT = 1, /*!< MSDK get joystick control authority. */
DJI_FLIGHT_CONTROLLER_INTERNAL_GET_JOYSTICK_CTRL_AUTH_EVENT = 2, /*!< Special Internal modules get joystick control authority. */
DJI_FLIGHT_CONTROLLER_OSDK_GET_JOYSTICK_CTRL_AUTH_EVENT = 3, /*!< OSDK get joystick control authority. */
DJI_FLIGHT_CONTROLLER_RC_LOST_GET_JOYSTICK_CTRL_AUTH_EVENT = 4, /*!< Reset joystick control authority to rc when executing rc lost action */
DJI_FLIGHT_CONTROLLER_RC_NOT_P_MODE_RESET_JOYSTICK_CTRL_AUTH_EVENT = 5, /*!< Reset joystick control authority to rc when rc is not in P mode */
DJI_FLIGHT_CONTROLLER_RC_SWITCH_MODE_GET_JOYSTICK_CTRL_AUTH_EVENT = 6, /*!< Set joystick control authority to rc when rc switch control mode(T/APS) */
DJI_FLIGHT_CONTROLLER_RC_PAUSE_GET_JOYSTICK_CTRL_AUTH_EVENT = 7, /*!< Reset joystick control authority to rc when rc pausing */
DJI_FLIGHT_CONTROLLER_RC_REQUEST_GO_HOME_GET_JOYSTICK_CTRL_AUTH_EVENT = 8, /*!< Reset joystick control authority to rc when rc requesting go home*/
DJI_FLIGHT_CONTROLLER_LOW_BATTERY_GO_HOME_RESET_JOYSTICK_CTRL_AUTH_EVENT = 9, /*!< Reset joystick control authority to rc when aircraft is executing low-battery-go-home*/
DJI_FLIGHT_CONTROLLER_LOW_BATTERY_LANDING_RESET_JOYSTICK_CTRL_AUTH_EVENT = 10, /*!< Reset joystick control authority to rc when aircraft is executing low-battery-landing*/
DJI_FLIGHT_CONTROLLER_OSDK_LOST_GET_JOYSTICK_CTRL_AUTH_EVENT = 11, /*!< Reset joystick control authority to rc when osdk is lost*/
DJI_FLIGHT_CONTROLLER_NERA_FLIGHT_BOUNDARY_RESET_JOYSTICK_CTRL_AUTH_EVENT = 12, /*!< Reset joystick control authority to rc when aircraft is near boundary.*/
DJI_FLIGHT_CONTROLLER_MSDK_GET_JOYSTICK_CTRL_AUTH_EVENT = 1, /*!< MSDK gets the joystick control permission. */
DJI_FLIGHT_CONTROLLER_INTERNAL_GET_JOYSTICK_CTRL_AUTH_EVENT = 2, /*!< A specific internal modules gets the joystick control permission. */
DJI_FLIGHT_CONTROLLER_OSDK_GET_JOYSTICK_CTRL_AUTH_EVENT = 3, /*!< PSDK gets the joystick control permission. */
DJI_FLIGHT_CONTROLLER_RC_LOST_GET_JOYSTICK_CTRL_AUTH_EVENT = 4, /*!< Reset the joystick control permission to RC when executing RC lost action */
DJI_FLIGHT_CONTROLLER_RC_NOT_P_MODE_RESET_JOYSTICK_CTRL_AUTH_EVENT = 5, /*!< Reset the joystick control permission to RC when RC is not in P mode */
DJI_FLIGHT_CONTROLLER_RC_SWITCH_MODE_GET_JOYSTICK_CTRL_AUTH_EVENT = 6, /*!< Set the joystick control permission to RC when RC switches control mode(T/APS) */
DJI_FLIGHT_CONTROLLER_RC_PAUSE_GET_JOYSTICK_CTRL_AUTH_EVENT = 7, /*!< Reset the joystick control permission to RC when RC pauses */
DJI_FLIGHT_CONTROLLER_RC_REQUEST_GO_HOME_GET_JOYSTICK_CTRL_AUTH_EVENT = 8, /*!< Reset the joystick control permission to RC when RC requests to go home*/
DJI_FLIGHT_CONTROLLER_LOW_BATTERY_GO_HOME_RESET_JOYSTICK_CTRL_AUTH_EVENT = 9, /*!< Reset the joystick control permission to RC when aircraft is executing low-battery-go-home*/
DJI_FLIGHT_CONTROLLER_LOW_BATTERY_LANDING_RESET_JOYSTICK_CTRL_AUTH_EVENT = 10, /*!< Reset the joystick control permission to RC when aircraft is executing low-battery-landing*/
DJI_FLIGHT_CONTROLLER_OSDK_LOST_GET_JOYSTICK_CTRL_AUTH_EVENT = 11, /*!< Reset the joystick control permission to RC when PSDK is lost*/
DJI_FLIGHT_CONTROLLER_NERA_FLIGHT_BOUNDARY_RESET_JOYSTICK_CTRL_AUTH_EVENT = 12, /*!< Reset the joystick control permission to RC when aircraft is near boundary.*/
} E_DjiFlightControllerJoystickCtrlAuthoritySwitchEvent;
/**
* @brief The UAV's joystick control authority switch event info enum
* @brief The aircraft's joystick control permission switch event info enum
*/
typedef struct {
E_DjiFlightControllerJoystickCtrlAuthority curJoystickCtrlAuthority; /*!< The UAV's joystick control authority owner */
E_DjiFlightControllerJoystickCtrlAuthoritySwitchEvent joystickCtrlAuthoritySwitchEvent; /*!< The UAV's joystick control authority switch reason */
E_DjiFlightControllerJoystickCtrlAuthority curJoystickCtrlAuthority; /*!< The aircraft's joystick control permission owner */
E_DjiFlightControllerJoystickCtrlAuthoritySwitchEvent joystickCtrlAuthoritySwitchEvent; /*!< The aircraft's joystick control permission switch reason */
} T_DjiFlightControllerJoystickCtrlAuthorityEventInfo;
/**
* @brief Prototype of callback function used to get joystick control authority switch event info.
* @brief Prototype of callback function used to get joystick control permission switch event info.
* @return Execution result.
*/
typedef T_DjiReturnCode (*JoystickCtrlAuthorityEventCbFunc)(
T_DjiFlightControllerJoystickCtrlAuthorityEventInfo eventData);
/**
* @brief Prototype of callback function used to get the trigger FTS event.
* @return Execution result.
*/
typedef T_DjiReturnCode (*TriggerFtsEventCallback)(void);
/**
* @brief Horizon control mode in joystick mode enum
* @note Only when the GPS signal is good (health_flag >=3)horizontal position control (DJI_FLIGHT_CONTROLLER_HORIZONTAL_POSITION_CONTROL_MODE)
* related control modes can be used. only when GPS signal is good (health_flag >=3)or when advanced sensing system is working properly with Autopilot
* related control modes can be used. Only when GPS signal is good (health_flag >=3)or advanced sensing system is working properly with Autopilot
* horizontal velocity controlDJI_FLIGHT_CONTROLLER_HORIZONTAL_VELOCITY_CONTROL_MODE) related control modes can be used.
*/
typedef enum {
@ -145,19 +151,19 @@ typedef enum {
*/
DJI_FLIGHT_CONTROLLER_HORIZONTAL_ANGLE_CONTROL_MODE = 0,
/**
* @brief Set the control-mode to control horizontal vehicle velocities.
* @brief Set the control mode to control horizontal vehicle velocities.
* @note Need to be referenced to either the ground or body frame by E_DjiFlightControllerHorizontalCoordinate setting
* Limit: -30m/s to 30 m/s
*/
DJI_FLIGHT_CONTROLLER_HORIZONTAL_VELOCITY_CONTROL_MODE = 1,
/**
* @brief Set the control-mode to control position offsets of pitch & roll directions.
* @brief Set the control mode to control position offsets of pitch & roll directions.
* @note Need to be referenced to either the ground or body frame by E_DjiFlightControllerHorizontalCoordinate setting
* Limit: N/A
*/
DJI_FLIGHT_CONTROLLER_HORIZONTAL_POSITION_CONTROL_MODE = 2,
/**
* @brief Set the control-mode to control rate of change of the vehicle's attitude.
* @brief Set the control mode to control rate of change of the vehicle's attitude.
* @note Need to be referenced to either the ground or body frame by E_DjiFlightControllerHorizontalCoordinate setting
* Limit: -150deg/s to 150.0 deg/s
*/
@ -165,51 +171,50 @@ typedef enum {
} E_DjiFlightControllerHorizontalControlMode;
/**
* @brief Vertical control mode in joystick mode enum
* @note We suggest developers do not use VERTICAL_POSITION control mode indoor when your UAV flight height is larger than 3 meters.
* This is because in indoor environments, barometer can be inaccurate, and the vertical controller may fail to keep
* the height of the UAV.
* @brief Vertical control mode enum in joystick mode
* @note We don not recommend using VERTICAL_POSITION control mode indoors when the aircraft's flying height exceeds 3 meters.
* This is because barometer can be inaccurate indoors, and the vertical controller may fail to keep the height of the aircraft.
*/
typedef enum {
/**
* @brief Set the control-mode to control the vertical speed of UAV, upward is positive/
* @note Limit: -5m/s to 5 m/s
* @brief Set the control mode to control the vertical speed of aircraft, setting the upward as positive/
* @note Limit: -5 m/s to 5 m/s
*/
DJI_FLIGHT_CONTROLLER_VERTICAL_VELOCITY_CONTROL_MODE = 0,
/**
* @brief Set the control-mode to control the height of UAV
* @note Limit: 0m to 120 m
* @brief Set the control mode to control the height of aircraft
* @note Limit: 0 m to 120 m
*/
DJI_FLIGHT_CONTROLLER_VERTICAL_POSITION_CONTROL_MODE = 1,
/**
* @brief Set the control-mode to directly control the thrust
* @note Range: 0% to 100%
* @brief Set the control mode to directly control the thrust
* @note Range: 0 % to 100 %
*/
DJI_FLIGHT_CONTROLLER_VERTICAL_THRUST_CONTROL_MODE = 2,
} E_DjiFlightControllerVerticalControlMode;
/**
* @brief Yaw control mode in joystick mode enum
* @brief Yaw control mode enum in joystick mode
*/
typedef enum {
/**
* @brief Set the control-mode to control yaw angle.
* @note Yaw angle is referenced to the ground frame.In this control mode, Ground frame is enforced in Autopilot.
* @brief Set the control mode to control yaw angle.
* @note Yaw angle is referenced to the ground frame. In this control mode, Ground frame is enforced in Autopilot.
*/
DJI_FLIGHT_CONTROLLER_YAW_ANGLE_CONTROL_MODE = 0x00,
/**
* @brief Set the control-mode to control yaw angular velocity
* @note Same reference frame as YAW_ANGLE.
* Limit: -150deg/s to 150 deg/s
* Limit: -150 deg/s to 150 deg/s
*/
DJI_FLIGHT_CONTROLLER_YAW_ANGLE_RATE_CONTROL_MODE = 1
} E_DjiFlightControllerYawControlMode;
/**
* @brief Horizontal coordinate in joystick mode enum
* @brief Horizontal coordinate enum in joystick mode
*/
typedef enum {
DJI_FLIGHT_CONTROLLER_HORIZONTAL_GROUND_COORDINATE = 0, /*!< Set the x-y of ground frame as the horizontal frame (NEU) */
@ -217,10 +222,10 @@ typedef enum {
} E_DjiFlightControllerHorizontalCoordinate;
/*!
* @brief Stable mode in joystick mode enum.
* @note Only works in Horizontal velocity control mode.In velocity stable mode, drone will brake and hover at one position once
* the input command is zero.In velocity non-stable mode, drone will follow the velocity command and not hover when the command is zero.
* That means drone will drift with the wind.
* @brief Stable mode enum in joystick mode
* @note Only works in horizontal velocity control mode. In velocity stable mode, aircraft will brake and hover at one position once
* the input command is zero. In velocity non-stable mode, aircraft will follow the velocity command and not hover when the command is zero.
* That means aircraft will drift with the wind.
*/
typedef enum {
DJI_FLIGHT_CONTROLLER_STABLE_CONTROL_MODE_DISABLE = 0, /*!< Disable the stable mode */
@ -246,9 +251,9 @@ typedef struct {
#pragma pack(1)
typedef struct {
dji_f32_t x; /*!< Control with respect to the x axis.*/
dji_f32_t y; /*!< Control with respect to the y axis.*/
dji_f32_t z; /*!< Control with respect to the z axis, up is positive. */
dji_f32_t x; /*!< Controls the x axis.*/
dji_f32_t y; /*!< Controls the y axis.*/
dji_f32_t z; /*!< Controls the z axis, setting upward as positive. */
dji_f32_t yaw; /*!< Yaw position/velocity control w.r.t. the ground frame.*/
} T_DjiFlightControllerJoystickCommand;// pack(1)
@ -260,27 +265,33 @@ typedef struct {
typedef struct {
char serialNum[32];
} T_DjiFlightControllerGeneralInfo;
typedef struct {
dji_f64_t latitude; /*!< unit: rad */
dji_f64_t longitude; /*!< unit: rad */
uint16_t altitude;
} T_DjiFlightControllerRidInfo;
#pragma pack()
/* Exported functions --------------------------------------------------------*/
/**
* @brief Initialise flight controller module, and user should call this function
* before using flight controller features.
* @brief Initialise flight controller module
* @param ridInfo: Must report the correct RID information before using PSDK to control the aircraft.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_Init(void);
T_DjiReturnCode DjiFlightController_Init(T_DjiFlightControllerRidInfo ridInfo);
/**
* @brief DeInitialise flight controller module.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_Deinit(void);
T_DjiReturnCode DjiFlightController_DeInit(void);
/**
* @brief Enable/Disable RTK position function.
* @details Enabling RTK means that RTK data will be used instead of GPS during flight.
* @param rtkEnableStatus: see reference of "E_DjiFlightControllerRtkPositionEnableStatus".
* It keeps in sync with pilot's param.
* @param rtkEnableStatus: refer to "E_DjiFlightControllerRtkPositionEnableStatus", inheriting from Pilot.
* @return Execution result.
*/
T_DjiReturnCode
@ -289,164 +300,163 @@ DjiFlightController_SetRtkPositionEnableStatus(E_DjiFlightControllerRtkPositionE
/**
* @brief Get RTK enable status.
* @note Enabling RTK means that RTK data will be used during intelligent flight.
* @param rtkEnableStatus: see reference of "E_DjiFlightControllerRtkPositionEnableStatus".
* It keeps in sync with pilot's param.
* @param rtkEnableStatus: refer to "E_DjiFlightControllerRtkPositionEnableStatus", inheriting from Pilot.
* @return Execution result.
*/
T_DjiReturnCode
DjiFlightController_GetRtkPositionEnableStatus(E_DjiFlightControllerRtkPositionEnableStatus *rtkEnableStatus);
/**
* @brief Set rc lost action.
* @note It will be valid when rc and osdk is both lost.It only support M30.
* @param rcLostAction: actions when rc is lost.(hover/landing/go home).It keeps in sync with pilot's param.
* @brief Set RC lost action.
* @note Valid when RC and PSDK are both lost. It only supports M30.
* @param rcLostAction: actions when RC is lost.(hover/landing/go home).It inherits from Pilot's param.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_SetRCLostAction(E_DjiFlightControllerRCLostAction rcLostAction);
/**
* @brief Get rc lost action(hover/landing/gohome).
* @note It will be valid when rc and osdk is both lost.It only support M30.
* @param rcLostAction: see reference of E_DjiFlightControllerRCLostAction.It keeps in sync with pilot's param.
* @brief Get RC lost action(hover/landing/gohome).
* @note Valid when RC and PSDK are both lost. It only supports M30.
* @param rcLostAction: see reference of E_DjiFlightControllerRCLostAction.It inherits from Pilot's param.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_GetRCLostAction(E_DjiFlightControllerRCLostAction *rcLostAction);
/**
* @brief Enable/Disable horizontal visual(forwards,backwards,left,right) obstacle avoidance.
* @note For detailed parameters of obstacle avoidance, it is recommended to read the official user manual in
* @brief Enable/Disable horizontal visual(forwards,backwards,left,right) obstacle sensing.
* @note For detailed parameters of obstacle sensing, it is recommended to read the official user manual in
* https://www.dji.com.
* @param horizontalObstacleAvoidanceEnableStatus: see reference of E_DjiFlightControllerObstacleAvoidanceEnableStatus.
* It keeps in sync with pilot's param.
* It inherits from Pilot's param.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_SetHorizontalVisualObstacleAvoidanceEnableStatus(
E_DjiFlightControllerObstacleAvoidanceEnableStatus horizontalObstacleAvoidanceEnableStatus);
/**
* @brief Get status of horizontal visual(forwards,backwards,left,right) obstacle avoidance switch.
* @note For detailed parameters of obstacle avoidance, it is recommended to read the official user manual in
* @brief Get the switch status of horizontal visual(forwards,backwards,left,right) obstacle sensing.
* @note For detailed parameters of obstacle sensing, it is recommended to read the official user manual in
* https://www.dji.com.
* @param horizontalObstacleAvoidanceEnableStatus: see reference of E_DjiFlightControllerObstacleAvoidanceEnableStatus.
* It keeps in sync with pilot's param.
* It inherits from Pilot's param.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_GetHorizontalVisualObstacleAvoidanceEnableStatus(
E_DjiFlightControllerObstacleAvoidanceEnableStatus *horizontalObstacleAvoidanceEnableStatus);
/**
* @brief Enable/Disable horizontal radar obstacle avoidance.
* @note It will be valid only if you install CSM radar successfully.For detailed parameters of obstacle avoidance,
* it is recommended to read the official user manual in https://www.dji.com/uk/matrice-300/downloads.
* @brief Enable/Disable horizontal radar obstacle sensing.
* @note It will be valid only if you install CSM radar successfully.For detailed parameters of obstacle sensing,
* it is recommended to read the official user manual in https://www.dji.com.
* @param horizontalObstacleAvoidanceEnableStatus: see reference of E_DjiFlightControllerObstacleAvoidanceEnableStatus.
* It keeps in sync with pilot's param.
* It inherits from Pilot's param.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_SetHorizontalRadarObstacleAvoidanceEnableStatus(
E_DjiFlightControllerObstacleAvoidanceEnableStatus horizontalObstacleAvoidanceEnableStatus);
/**
* @brief Get status of horizontal radar obstacle avoidance switch.
* @note It will be valid only if you install CSM radar successfully.For detailed parameters of obstacle avoidance,
* @brief Get the switch status of horizontal radar obstacle sensing.
* @note It will be valid only if you install CSM radar successfully.For detailed parameters of obstacle sensing,
* it is recommended to read the official user manual in https://www.dji.com/uk/matrice-300/downloads.
* @param horizontalObstacleAvoidanceEnableStatus: see reference of E_DjiFlightControllerObstacleAvoidanceEnableStatus.
* It keeps in sync with pilot's param.
* It inherits from Pilot's param.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_GetHorizontalRadarObstacleAvoidanceEnableStatus(
E_DjiFlightControllerObstacleAvoidanceEnableStatus *horizontalObstacleAvoidanceEnableStatus);
/**
* @brief Enable/Disable upwards visual obstacle avoidance.
* @note For detailed parameters of obstacle avoidance, it is recommended to read the official user manual in
* @brief Enable/Disable upwards visual obstacle sensing.
* @note For detailed parameters of obstacle sensing, it is recommended to read the official user manual in
* https://www.dji.com.
* @param upwardsObstacleAvoidanceEnableStatus: see reference of E_DjiFlightControllerObstacleAvoidanceEnableStatus.
* It keeps in sync with pilot's param.
* It inherits from Pilot's param.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_SetUpwardsVisualObstacleAvoidanceEnableStatus(
E_DjiFlightControllerObstacleAvoidanceEnableStatus upwardsObstacleAvoidanceEnableStatus);
/**
* @brief Get status of upwards visual obstacle avoidance switch.
* @note For detailed parameters of obstacle avoidance, it is recommended to read the official user manual in
* @brief Get the switch status of upwards visual obstacle sensing.
* @note For detailed parameters of obstacle sensing, it is recommended to read the official user manual in
* https://www.dji.com.
* @param upwardsObstacleAvoidanceEnableStatus: see reference of E_DjiFlightControllerObstacleAvoidanceEnableStatus.
* It keeps in sync with pilot's param.
* It inherits from Pilot's param.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_GetUpwardsVisualObstacleAvoidanceEnableStatus(
E_DjiFlightControllerObstacleAvoidanceEnableStatus *upwardsObstacleAvoidanceEnableStatus);
/**
* @brief Enable/Disable upwards radar obstacle avoidance.
* @note It will be valid only if you install CSM radar successfully.For detailed parameters of obstacle avoidance,
* @brief Enable/Disable upwards radar obstacle sensing.
* @note It will be valid only if you install CSM radar successfully.For detailed parameters of obstacle sensing,
* it is recommended to read the official user manual in https://www.dji.com.
* @param upwardsObstacleAvoidanceEnableStatus: see reference of E_DjiFlightControllerObstacleAvoidanceEnableStatus.
* It keeps in sync with pilot's param.
* It inherits from Pilot's param.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_SetUpwardsRadarObstacleAvoidanceEnableStatus(
E_DjiFlightControllerObstacleAvoidanceEnableStatus upwardsObstacleAvoidanceEnableStatus);
/**
* @brief Get status of upwards radar obstacle avoidance switch
* @note For detailed parameters of obstacle avoidance, it is recommended to read the official user manual in
* @brief Get the switch status of upwards radar obstacle sensing.
* @note For detailed parameters of obstacle sensing, it is recommended to read the official user manual in
* https://www.dji.com.
* @param upwardsObstacleAvoidanceEnableStatus: see reference of E_DjiFlightControllerObstacleAvoidanceEnableStatus.
* It keeps in sync with pilot's param.
* It inherits from Pilot's param.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_GetUpwardsRadarObstacleAvoidanceEnableStatus(
E_DjiFlightControllerObstacleAvoidanceEnableStatus *upwardsObstacleAvoidanceEnableStatus);
/**
* @brief Enable/Disable downwards visual obstacle avoidance
* @note For detailed parameters of obstacle avoidance, it is recommended to read the official user manual in
* @brief Enable/Disable downwards visual obstacle sensing.
* @note For detailed parameters of obstacle sensing, it is recommended to read the official user manual in
* https://www.dji.com.
* @param downwardsObstacleAvoidanceEnableStatus: see reference of E_DjiFlightControllerObstacleAvoidanceEnableStatus.
* It keeps in sync with pilot's param.
* It inherits from Pilot's param.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_SetDownwardsVisualObstacleAvoidanceEnableStatus(
E_DjiFlightControllerObstacleAvoidanceEnableStatus downwardsObstacleAvoidanceEnableStatus);
/**
* @brief Get status of downwards visual obstacle avoidance switch
* @note For detailed parameters of obstacle avoidance, it is recommended to read the official user manual in
* @brief Get the switch status of downwards visual obstacle sensing.
* @note For detailed parameters of obstacle sensing, it is recommended to read the official user manual in
* https://www.dji.com.
* @param downwardsObstacleAvoidanceEnableStatus: see reference of E_DjiFlightControllerObstacleAvoidanceEnableStatus.
* It keeps in sync with pilot's param.
* It inherits from Pilot's param.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_GetDownwardsVisualObstacleAvoidanceEnableStatus(
E_DjiFlightControllerObstacleAvoidanceEnableStatus *downwardsObstacleAvoidanceEnableStatus);
/**
* @brief Arrest flying.
* @note when the UAV is on the ground ,it will stop motors and display "hms description" on APP. when the UAV is
* in the air, it will continue flying and display "hms description" on APP only.
* @brief Arrest flying means emergency braking
* @note When the aircraft is on the ground, it will stop motors and display "hms description" on App. when the aircraft is
* in the air, it will continue flying and display "hms description" on App only.
* If you use this interface, you need to use "DjiFlightController_CancelArrestFlying" to quit arrest-flying status, then
* then the UAV can fly again.
* then the aircraft can fly again.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_ArrestFlying(void);
/**
* @brief Quit status of arrest-flying.
* @note The UAV need to quit status of arrest-flying to continue flying after arresting flying.
* @note The aircraft need to quit status of arrest-flying to continue flying after arresting flying.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_CancelArrestFlying(void);
/**
* @brief Turn on motors when the UAV is on the ground.
* @brief Turn on motors when the aircraft is on the ground.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_TurnOnMotors(void);
/**
* @brief Turn off motors when the UAV is on the ground.
* @brief Turn off motors when the aircraft is on the ground.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_TurnOffMotors(void);
@ -462,36 +472,36 @@ T_DjiReturnCode DjiFlightController_TurnOffMotors(void);
T_DjiReturnCode DjiFlightController_EmergencyStopMotor(E_DjiFlightControllerEmergencyStopMotor cmd,
char debugMsg[EMERGENCY_STOP_MOTOR_MSG_MAX_LENGTH]);
/**
* @brief Request take off action when the UAV is on the ground.
* @brief Request taking off action when the aircraft is on the ground.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_StartTakeoff(void);
/**
* @brief Request landing action when the UAV is in the air.
* @brief Request landing action when the aircraft is in the air.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_StartLanding(void);
/**
* @brief Request cancel landing action when the UAV is landing
* @brief Request cancelling landing action when the aircraft is landing
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_CancelLanding(void);
/**
* @brief Confirm the landing when the UAV is 0.7m above the ground.
* @brief Confirm the landing when the aircraft is 0.7 m above the ground.
* @note When the clearance between the aircraft and the ground is less than 0.7m, the aircraft will pause landing and
* wait for user's confirmation.This api use for confirm landing. If the ground is not suitable for landing ,user must
* use RC to control it landing manually or force landing.
* wait for user's confirmation. This API is for confirm landing. If the ground is not suitable for landing, user
* must use RC to control it landing manually or force landing.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_StartConfirmLanding(void);
/**
* @brief Force landing in any case.
* @note This api will ignore the smart landing function,.When using this pi, it will landing directly (would not stop
* at 0.7m and wait user's command). Attention:it may make the aircraft crash!!!
* @note This API will ignore the smart landing function. When using this API, it will landing directly (would not stop
* at 0.7m and wait user's command). Attention: it may make the aircraft crash!!!
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_StartForceLanding(void);
@ -499,7 +509,7 @@ T_DjiReturnCode DjiFlightController_StartForceLanding(void);
/**
* @brief Set customized GPS(not RTK) home location.
* @note Set customized home location failed reason may as follows:
* 1. The distance between new home location and last home location is larger than MAX_FLY_RADIUS(20km).
* 1. The distance between new home location and last home location is larger than MAX_FLY_RADIUS(20 km).
* 2. Record initial home location failed after start aircraft.
* @param homeLocation: homeLocation include latitude and longitude
* @return Execution result.
@ -507,7 +517,7 @@ T_DjiReturnCode DjiFlightController_StartForceLanding(void);
T_DjiReturnCode DjiFlightController_SetHomeLocationUsingGPSCoordinates(T_DjiFlightControllerHomeLocation homeLocation);
/**
* @brief Set home location using current aircraft GPS(not RTK) location.
* @brief Set home location using current aircraft GPS (not RTK) location.
* @note Set home location failed reasons may as follows:
* 1. Aircraft's gps level can't reach the condition of recording home location.
* 2. Record initial home location failed after start aircraft.
@ -519,7 +529,7 @@ T_DjiReturnCode DjiFlightController_SetHomeLocationUsingCurrentAircraftLocation(
* @brief Set go home altitude.
* @note If aircraft's current altitude is higher than the setting value of go home altitude, aircraft will go home
* using current altitude. Otherwise, it will climb to setting of go home altitude ,and then execute go home action.
* Go home altitude setting is 20m ~ 500m.
* Go home altitude setting is 20-1500 m.
* @param altitude: go home altitude, unit: meter
* @return Execution result.
*/
@ -533,35 +543,44 @@ T_DjiReturnCode DjiFlightController_SetGoHomeAltitude(E_DjiFlightControllerGoHom
T_DjiReturnCode DjiFlightController_GetGoHomeAltitude(E_DjiFlightControllerGoHomeAltitude *altitude);
/**
* @brief Request go home action when the UAV is in the air
* @brief Get country code.
* @param countryCode: Pointer of buffer to return country code. The country code indicates the current country or
* region where the aircraft is located. Please refer to the ISO 3166-1 code table for the specific meaning of the
* country code.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_GetCountryCode(uint16_t *countryCode);
/**
* @brief Request go home action when the aircraft is in the air
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_StartGoHome(void);
/**
* @brief Request cancel go home action when the UAV is going home
* @brief Request cancel go home action when the aircraft is going home
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_CancelGoHome(void);
/**
* @brief Obtain UAV's joystick control authority.
* @note 1.You have to obtain joystick control authority successfully before you using joystick to control UAV.
* @brief Obtain aircraft's joystick control permission.
* @note 1.You have to obtain joystick control permission successfully before you using joystick to control aircraft.
* 2. RC must be in p-mode.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_ObtainJoystickCtrlAuthority(void);
/**
* @brief Release UAV's joystick control authority.
* @brief Release aircraft's joystick control permission.
* @note RC must be in p-mode.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_ReleaseJoystickCtrlAuthority(void);
/**
* @brief Subscribe to joystick control authority switch event with a callback function.
* @note it will be triggered once the joystick control authority switch event occurs.
* @brief Subscribe to joystick control permission switch event with a callback function.
* @note it will be triggered once the joystick control permission switch event occurs.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_RegJoystickCtrlAuthorityEventCallback(JoystickCtrlAuthorityEventCbFunc callback);
@ -588,7 +607,7 @@ T_DjiReturnCode DjiFlightController_ExecuteEmergencyBrakeAction(void);
/**
* @brief Request cancel emergency brake action.
* @note It is only support on M30.If you use DjiFlightController_ExecuteEmergencyBrakeAction(), you need to use
* "DjiFlightController_CancelEmergencyBrakeAction()" to allow aircraft to execute drone action again.
* "DjiFlightController_CancelEmergencyBrakeAction()" to allow aircraft to execute aircraft action again.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_CancelEmergencyBrakeAction(void);
@ -601,11 +620,11 @@ T_DjiReturnCode DjiFlightController_CancelEmergencyBrakeAction(void);
*/
T_DjiReturnCode DjiFlightController_GetGeneralInfo(T_DjiFlightControllerGeneralInfo *generalInfo);
/*! @brief The command decides whether execute RC lost action or not when osdk is running
* @note This setting only affects the behavior of the drone when the RC lost and the OSDK is connected.
* if the command is enable, the drone will not execute rc lost action when rc is lost but OSDK is running;
* if the command is disable, the drone will execute rc lost action when rc is lost but OSDK is running
* the drone will execute rc lost action when rc is lost and OSDK is lost whatever the command is.
/*! @brief The command decides whether execute RC lost action or not when PSDK is running
* @note This setting only affects the behavior of the aircraft when the RC lost and the PSDK is connected.
* if the command is enable, the aircraft will not execute RC lost action when RC is lost but PSDK is running;
* if the command is disable, the aircraft will execute RC lost action when RC is lost but PSDK is running
* the aircraft will execute RC lost action when RC is lost and PSDK is lost whatever the command is.
* default command is disable.
* @param executeRCLostActionOrNotWhenOnboardOn enable:1;disable:0
* @return T_DjiReturnCode error code
@ -613,13 +632,23 @@ T_DjiReturnCode DjiFlightController_GetGeneralInfo(T_DjiFlightControllerGeneralI
T_DjiReturnCode
DjiFlightController_SetRCLostActionEnableStatus(E_DjiFlightControllerRCLostActionEnableStatus command);
/*! @brief get rc lost action enable status(enable or disable)
/*! @brief get RC lost action enable status(enable or disable)
* @param command executeRCLostActionOrNotWhenOnboardOn, enable:1;disable:0
* @return T_DjiReturnCode error code
*/
T_DjiReturnCode
DjiFlightController_GetEnableRCLostActionStatus(E_DjiFlightControllerRCLostActionEnableStatus *command);
/**
* @brief Register callback function for the trigger FTS event.
* @note The timing of the trigger of the callback function of the FTS is determined by the aircraft, and the trigger
* execution action of the FTS needs to be implemented in the callback function and the correct return value
* must be returned, otherwise the aircraft will always be triggered.
* @param callback: the callback for the trigger FTS event.
* @return Execution result.
*/
T_DjiReturnCode DjiFlightController_RegTriggerFtsEventCallback(TriggerFtsEventCallback callback);
#ifdef __cplusplus
}
#endif

View File

@ -66,6 +66,12 @@ typedef enum {
/*! Reset yaw axis and pitch axis of gimbal. Reset angle of yaw axis to sum of yaw axis angle of aircraft and fine tune
* angle of yaw axis of gimbal, and reset pitch axis angle to the fine tune angle. */
DJI_GIMBAL_RESET_MODE_PITCH_AND_YAW = 3,
/*! Reset only pitch axis of gimbal. */
DJI_GIMBAL_RESET_MODE_PITCH_ONLY = 4,
/*! Reset only roll axis of gimbal. */
DJI_GIMBAL_RESET_MODE_ROLL_ONLY = 5,
/*! Reset only yaw axis of gimbal. */
DJI_GIMBAL_RESET_MODE_YAW_ONLY = 6,
/*! Reset yaw axis and pitch axis of gimbal. Reset angle of yaw axis to sum of yaw axis angle of aircraft and fine tune
* angle of yaw axis of gimbal, and reset pitch axis angle to sum of -90 degree and fine tune angle if gimbal
* downward, sum of 90 degree and fine tune angle if upward. */

View File

@ -28,6 +28,7 @@
#define DJI_GIMBAL_MANAGER_H
/* Includes ------------------------------------------------------------------*/
#include <dji_gimbal.h>
#include "dji_typedef.h"
#ifdef __cplusplus
@ -45,13 +46,13 @@ typedef struct {
dji_f32_t pitch; /*!< Pitch angle in degree, unit: deg */
dji_f32_t roll; /*!< Roll angle in degree, unit: deg */
dji_f32_t yaw; /*!< Yaw angle in degree, unit: deg */
dji_f64_t time; /*!< Expect execution time of gimbal rotation, unit: second. */
dji_f64_t time; /*!< Expected execution time for gimbal rotation, in seconds. */
} T_DjiGimbalManagerRotation;
/* Exported functions --------------------------------------------------------*/
/**
* @brief Initialize the gimbal manager module.
* @note The interface initialization needs to be after DjiCore_Init.
* @note This interface must be initialized after DjiCore_Init.
* @return Execution result.
*/
T_DjiReturnCode DjiGimbalManager_Init(void);
@ -73,19 +74,60 @@ T_DjiReturnCode DjiGimbalManager_SetMode(E_DjiMountPosition mountPosition, E_Dji
/**
* @brief Reset the pitch and yaw of the gimbal.
* @param mountPosition: gimbal mount position, input limit see enum E_DjiMountPosition
* @param mode: reset mode, input limit see enum E_DjiGimbalResetMode
* @return Execution result.
*/
T_DjiReturnCode DjiGimbalManager_Reset(E_DjiMountPosition mountPosition);
T_DjiReturnCode DjiGimbalManager_Reset(E_DjiMountPosition mountPosition, E_DjiGimbalResetMode resetMode);
/**
* @brief Rotate the angle of the gimbal.
* @param mountPosition: gimbal mount position, input limit see enum E_DjiMountPosition
* @param rotation: the rotation parameters to be executed on the target gimbal, including the rotation mode, target
* angle value and executed time, ref to T_DjiGimbalManagerRotation
* angle value and executed time, refer to T_DjiGimbalManagerRotation
* @return Execution result.
*/
T_DjiReturnCode DjiGimbalManager_Rotate(E_DjiMountPosition mountPosition, T_DjiGimbalManagerRotation rotation);
/*!
* @brief Prototype of callback function used to enable or disable extended pitch axis angle range.
* @note Switching the gimbal limit euler angle of pitch axis to the extended limit angle or the default limit
* angle.
* @param mountPosition: gimbal mount position, input limit see enum E_DjiMountPosition
* @param enabledFlag: flag specifying whether to enable or disable the extended pitch axis angle range..
* @return Execution result.
*/
T_DjiReturnCode DjiGimbalManager_SetPitchRangeExtensionEnabled(E_DjiMountPosition mountPosition, bool enabledFlag);
/**
* @brief Set max speed percentage for gimbal controller.
* @param mountPosition: gimbal mount position, input limit see enum E_DjiMountPosition
* @param axis: axis to be set.
* @param maxSpeedPercentage: max speed value. Recommended calculation formula is "spd = default_max_spd * x / 100",
* where 'x' is the default maximum speed value. Range from 1 to 100.
* @return Execution result.
*/
T_DjiReturnCode DjiGimbalManager_SetControllerMaxSpeedPercentage(E_DjiMountPosition mountPosition, E_DjiGimbalAxis axis,
uint8_t maxSpeedPercentage);
/**
* @brief Set smooth factor for gimbal controller, using for smooth control.
* @param mountPosition: gimbal mount position, input limit see enum E_DjiMountPosition
* @param axis: axis to be set.
* @param smoothingFactor: smooth factor. A larger value results in slower gimbal acceleration. Recommended
* calculation formula is "acc = 10000 * (0.8 ^ (1 + x)) deg/s^2", x is smooth factor. Range from 0 to 30.
* @return Execution result.
*/
T_DjiReturnCode DjiGimbalManager_SetControllerSmoothFactor(E_DjiMountPosition mountPosition, E_DjiGimbalAxis axis,
uint8_t smoothingFactor);
/**
* @brief Restore factory settings of gimbal, including fine tune angle, pitch angle extension enable flag and max
* speed etc.
* @param mountPosition: gimbal mount position, input limit see enum E_DjiMountPosition
* @return Execution result.
*/
T_DjiReturnCode DjiGimbalManager_RestoreFactorySettings(E_DjiMountPosition mountPosition);
#ifdef __cplusplus
}
#endif

View File

@ -29,6 +29,8 @@
/* Includes ------------------------------------------------------------------*/
#include "dji_typedef.h"
#include "dji_hms_customization.h"
#include "dji_hms_manager.h"
#ifdef __cplusplus
extern "C" {
@ -37,113 +39,8 @@ extern "C" {
/* Exported constants --------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
typedef enum {
DJI_HMS_ERROR_LEVEL_NONE = 0,
DJI_HMS_ERROR_LEVEL_HINT,
DJI_HMS_ERROR_LEVEL_WARN,
DJI_HMS_ERROR_LEVEL_CRITICAL,
DJI_HMS_ERROR_LEVEL_FATAL,
} E_DjiHmsErrorLevel;
typedef struct {
uint32_t errorCode;
uint8_t componentIndex;
uint8_t errorLevel;
} T_DjiHmsInfo;
typedef struct {
T_DjiHmsInfo *hmsInfo;
uint32_t hmsInfoNum;
} T_DjiHmsInfoTable;
typedef struct {
char *fileName; /*!< The file name of the hms text config file */
uint32_t fileSize; /*!< The file size of the hms text config file, uint : byte */
const uint8_t *fileBinaryArray; /*!< The binary C array of the hms text config file */
} T_DjiHmsFileBinaryArray;
typedef struct {
uint16_t binaryArrayCount; /*!< Binary array count. */
T_DjiHmsFileBinaryArray *fileBinaryArrayList; /*!< Pointer to binary array list */
} T_DjiHmsBinaryArrayConfig;
typedef T_DjiReturnCode (*DjiHmsInfoCallback)(T_DjiHmsInfoTable hmsInfoTable);
/* Exported functions --------------------------------------------------------*/
/**
* @brief Initialise hms module, and user should call this function
* before using hms features.
* @return Execution result.
*/
T_DjiReturnCode DjiHms_Init(void);
/**
* @brief Deinitialise hms module.
* @return Execution result.
*/
T_DjiReturnCode DjiHms_DeInit(void);
/**
* @brief Register callback to get hms info.
* @note: Data is pushed with a frequency of 1Hz.
* @param callback: see reference of DjiHmsInfoCallback.
* @return Execution result.
*/
T_DjiReturnCode DjiHms_RegHmsInfoCallback(DjiHmsInfoCallback callback);
/**
* @brief Inject custom hms error code to APP.
* @note: For the same hms error code, a single call is enough, no need to call repeatedly.
* @param errorCode: hms error code, value range: [0x1E020000 ~ 0x1E02FFFF].
* @param errorLevel: hms error level, see reference of E_DjiHmsErrorLevel.
* @return Execution result.
*/
T_DjiReturnCode DjiHms_InjectHmsErrorCode(uint32_t errorCode, E_DjiHmsErrorLevel errorLevel);
/**
* @brief Eliminate custom hms error code to APP.
* @note: For the same hms error code, a single call is enough, no need to call repeatedly.
* @param errorCode: hms error code, value range: [0x1E020000 ~ 0x1E02FFFF].
* @return Execution result.
*/
T_DjiReturnCode DjiHms_EliminateHmsErrorCode(uint32_t errorCode);
/**
* @brief Register default hms text configuration file by directory path.
* @param configDirPath: the hms text configuration by directory path.
* @return Execution result.
*/
T_DjiReturnCode DjiHms_RegDefaultHmsTextConfigByDirPath(const char *configDirPath);
/**
* @brief Register hms text configuration file by directory path.
* @note Different hms text configurations for several language require the same hms config.
* @param appLanguage: mobile app language type.
* @param configDirPath: the hms text configuration by directory path.
* @return Execution result.
*/
T_DjiReturnCode DjiHms_RegHmsTextConfigByDirPath(E_DjiMobileAppLanguage appLanguage,
const char *configDirPath);
/**
* @brief Register default hms text configuration config by binary array.
* @note In RTOS, most likely there is no file system. The hms text config file content can use C array express. Use this
* function and DjiHms_RegDefaultHmsTextConfigByBinaryArray set hms text configuration. When the language is not cover in
* your setting by DjiHms_RegHmsTextConfigByBinaryArray, the hms text configuration uses setting by this function.
* @param binaryArrayConfig: the binary array config for hms text configuration.
* @return Execution result.
*/
T_DjiReturnCode DjiHms_RegDefaultHmsTextConfigByBinaryArray(const T_DjiHmsBinaryArrayConfig *binaryArrayConfig);
/**
* @brief Register hms text config by binary array configuration.
* @note Different hms text configurations for several language require the same hms config.
* @param appLanguage: mobile app language type.
* @param binaryArrayConfig: the binary array config for hms text configuration.
* @return Execution result.
*/
T_DjiReturnCode DjiHms_RegHmsTextConfigByBinaryArray(E_DjiMobileAppLanguage appLanguage,
const T_DjiHmsBinaryArrayConfig *binaryArrayConfig);
#ifdef __cplusplus
}

View File

@ -0,0 +1,133 @@
/**
********************************************************************
* @file dji_hms_customization.h
* @brief This is the header file for "dji_hms_customization.c", defining the structure and
* (exported) function prototypes.
*
* @copyright (c) 2018 DJI. All rights reserved.
*
* All information contained herein is, and remains, the property of DJI.
* The intellectual and technical concepts contained herein are proprietary
* to DJI and may be covered by U.S. and foreign patents, patents in process,
* and protected by trade secret or copyright law. Dissemination of this
* information, including but not limited to data and other proprietary
* material(s) incorporated within the information, in any form, is strictly
* prohibited without the express written consent of DJI.
*
* If you receive this source code without DJIs authorization, you may not
* further disseminate the information, and you must immediately remove the
* source code and notify DJI of its removal. DJI reserves the right to pursue
* legal actions against you for any loss(es) or damage(s) caused by your
* failure to do so.
*
*********************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef DJI_HMS_CUSTOMIZATION_H
#define DJI_HMS_CUSTOMIZATION_H
/* Includes ------------------------------------------------------------------*/
#ifdef __cplusplus
extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
typedef enum {
DJI_HMS_ERROR_LEVEL_NONE = 0,
DJI_HMS_ERROR_LEVEL_HINT,
DJI_HMS_ERROR_LEVEL_WARN,
DJI_HMS_ERROR_LEVEL_CRITICAL,
DJI_HMS_ERROR_LEVEL_FATAL,
} E_DjiHmsErrorLevel;
typedef struct {
char *fileName; /*!< The file name of the hms text config file */
uint32_t fileSize; /*!< The file size of the hms text config file, uint : byte */
const uint8_t *fileBinaryArray; /*!< The binary C array of the hms text config file */
} T_DjiHmsFileBinaryArray;
typedef struct {
uint16_t binaryArrayCount; /*!< Binary array count. */
T_DjiHmsFileBinaryArray *fileBinaryArrayList; /*!< Pointer to binary array list */
} T_DjiHmsBinaryArrayConfig;
/* Exported functions --------------------------------------------------------*/
/**
* @brief Initialise hms customization module, and user should call this function
* before using hms customization features.
* @return Execution result.
*/
T_DjiReturnCode DjiHmsCustomization_Init(void);
/**
* @brief DeInitialize hms manager module.
* @return Execution result.
*/
T_DjiReturnCode DjiHmsCustomization_DeInit(void);
/**
* @brief Inject custom hms error code to APP.
* @note: For the same hms error code, a single call is enough, no need to call repeatedly.
* @param errorCode: hms error code, value range: [0x1E020000 ~ 0x1E02FFFF].
* @param errorLevel: hms error level, see reference of E_DjiHmsErrorLevel.
* @return Execution result.
*/
T_DjiReturnCode DjiHmsCustomization_InjectHmsErrorCode(uint32_t errorCode, E_DjiHmsErrorLevel errorLevel);
/**
* @brief Eliminate custom hms error code to APP.
* @note: For the same hms error code, a single call is enough, no need to call repeatedly.
* @param errorCode: hms error code, value range: [0x1E020000 ~ 0x1E02FFFF].
* @return Execution result.
*/
T_DjiReturnCode DjiHmsCustomization_EliminateHmsErrorCode(uint32_t errorCode);
/**
* @brief Register default hms text configuration file by directory path.
* @param configDirPath: the hms text configuration by directory path.
* @return Execution result.
*/
T_DjiReturnCode DjiHmsCustomization_RegDefaultHmsTextConfigByDirPath(const char *configDirPath);
/**
* @brief Register hms text configuration file by directory path.
* @note Different hms text configurations for several language require the same hms config.
* @param appLanguage: mobile app language type.
* @param configDirPath: the hms text configuration by directory path.
* @return Execution result.
*/
T_DjiReturnCode DjiHmsCustomization_RegHmsTextConfigByDirPath(E_DjiMobileAppLanguage appLanguage,
const char *configDirPath);
/**
* @brief Register default hms text configuration config by binary array.
* @note In RTOS, most likely there is no file system. The hms text config file content can use C array express. Use this
* function and DjiHms_RegDefaultHmsTextConfigByBinaryArray set hms text configuration. When the language is not cover in
* your setting by DjiHms_RegHmsTextConfigByBinaryArray, the hms text configuration uses setting by this function.
* @param binaryArrayConfig: the binary array config for hms text configuration.
* @return Execution result.
*/
T_DjiReturnCode DjiHmsCustomization_RegDefaultHmsTextConfigByBinaryArray(const T_DjiHmsBinaryArrayConfig
*binaryArrayConfig);
/**
* @brief Register hms text config by binary array configuration.
* @note Different hms text configurations for several language require the same hms config.
* @param appLanguage: mobile app language type.
* @param binaryArrayConfig: the binary array config for hms text configuration.
* @return Execution result.
*/
T_DjiReturnCode DjiHmsCustomization_RegHmsTextConfigByBinaryArray(E_DjiMobileAppLanguage appLanguage,
const T_DjiHmsBinaryArrayConfig *binaryArrayConfig);
#ifdef __cplusplus
}
#endif
#endif // DJI_HMS_CUSTOMIZATION_H
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/

View File

@ -43,7 +43,9 @@ typedef struct {
const char *flyAlarmInfo; /*! alarm information when the flight is in the air*/
} T_DjiHmsErrCodeInfo;
/*! HMS's error code table*/
/*! Note: This api header file will not be maintained in the future, please refer to the latest hms error code file in
* the hms sample.
*/
const T_DjiHmsErrCodeInfo hmsErrCodeInfoTbl[] = {
{0x16070035, "Aircraft D-RTK antenna error. Fly with caution", ""},
{0x16070034, "RTK flight heading inconsistent with other sources. Fly with caution", ""},

View File

@ -0,0 +1,80 @@
/**
********************************************************************
* @file dji_hms_manager.h
* @brief This is the header file for "dji_hms_manager.c", defining the structure and
* (exported) function prototypes.
*
* @copyright (c) 2018 DJI. All rights reserved.
*
* All information contained herein is, and remains, the property of DJI.
* The intellectual and technical concepts contained herein are proprietary
* to DJI and may be covered by U.S. and foreign patents, patents in process,
* and protected by trade secret or copyright law. Dissemination of this
* information, including but not limited to data and other proprietary
* material(s) incorporated within the information, in any form, is strictly
* prohibited without the express written consent of DJI.
*
* If you receive this source code without DJIs authorization, you may not
* further disseminate the information, and you must immediately remove the
* source code and notify DJI of its removal. DJI reserves the right to pursue
* legal actions against you for any loss(es) or damage(s) caused by your
* failure to do so.
*
*********************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef DJI_HMS_MANAGER_H
#define DJI_HMS_MANAGER_H
/* Includes ------------------------------------------------------------------*/
#include "dji_typedef.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
typedef struct {
uint32_t errorCode;
uint8_t componentIndex;
uint8_t errorLevel;
} T_DjiHmsInfo;
typedef struct {
T_DjiHmsInfo *hmsInfo;
uint32_t hmsInfoNum;
} T_DjiHmsInfoTable;
typedef T_DjiReturnCode (*DjiHmsInfoCallback)(T_DjiHmsInfoTable hmsInfoTable);
/* Exported functions --------------------------------------------------------*/
/**
* @brief Initialise hms manager module, and user should call this function
* before using hms manager features.
* @return Execution result.
*/
T_DjiReturnCode DjiHmsManager_Init(void);
/**
* @brief DeInitialize hms manager module.
* @return Execution result.
*/
T_DjiReturnCode DjiHmsManager_DeInit(void);
/**
* @brief Register callback to get hms info.
* @note: Data is pushed with a frequency of 1Hz.
* @param callback: see reference of DjiHmsInfoCallback.
* @return Execution result.
*/
T_DjiReturnCode DjiHmsManager_RegHmsInfoCallback(DjiHmsInfoCallback callback);
#ifdef __cplusplus
}
#endif
#endif // DJI_HMS_MANAGER_H
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/

View File

@ -0,0 +1,74 @@
/**
********************************************************************
* @file dji_interest_point.h
* @version V1.0.0
* @date 2020/11/19
* @brief This is the header file for "dji_interest_point.c", defining the structure and
* (exported) function prototypes.
*
* @copyright (c) 2021 DJI. All rights reserved.
*
* All information contained herein is, and remains, the property of DJI.
* The intellectual and technical concepts contained herein are proprietary
* to DJI and may be covered by U.S. and foreign patents, patents in process,
* and protected by trade secret or copyright law. Dissemination of this
* information, including but not limited to data and other proprietary
* material(s) incorporated within the information, in any form, is strictly
* prohibited without the express written consent of DJI.
*
* If you receive this source code without DJIs authorization, you may not
* further disseminate the information, and you must immediately remove the
* source code and notify DJI of its removal. DJI reserves the right to pursue
* legal actions against you for any loss(es) or damage(s) caused by your
* failure to do so.
*
*********************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef DJI_INTEREST_POINT_H
#define DJI_INTEREST_POINT_H
/* Includes ------------------------------------------------------------------*/
#include "dji_platform.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
typedef struct {
dji_f32_t curSpeed;
dji_f32_t radius;
uint8_t state;
} T_DjiInterestPointMissionState;
typedef struct {
dji_f64_t latitude;
dji_f64_t longitude;
dji_f32_t speed;
} T_DjiInterestPointSettings;
typedef T_DjiReturnCode (*InterestPointMissionStateCallback)(T_DjiInterestPointMissionState missionState);
/* Exported functions --------------------------------------------------------*/
T_DjiReturnCode DjiInterestPoint_Init(void);
T_DjiReturnCode DjiInterestPoint_DeInit(void);
T_DjiReturnCode DjiInterestPoint_Start(T_DjiInterestPointSettings settings);
T_DjiReturnCode DjiInterestPoint_Stop(void);
T_DjiReturnCode DjiInterestPoint_SetSpeed(dji_f32_t speed);
T_DjiReturnCode DjiInterestPoint_RegMissionStateCallback(InterestPointMissionStateCallback callback);
#ifdef __cplusplus
}
#endif
#endif // DJI_INTEREST_POINT_H
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/

View File

@ -68,6 +68,9 @@ typedef enum {
DJI_LIVEVIEW_CAMERA_SOURCE_M3E_VIS = 1,
DJI_LIVEVIEW_CAMERA_SOURCE_M3T_VIS = 1,
DJI_LIVEVIEW_CAMERA_SOURCE_M3T_IR = 2,
DJI_LIVEVIEW_CAMERA_SOURCE_M3D_VIS = 1,
DJI_LIVEVIEW_CAMERA_SOURCE_M3TD_VIS = 1,
DJI_LIVEVIEW_CAMERA_SOURCE_M3TD_IR = 2,
} E_DjiLiveViewCameraSource;
/**
@ -78,7 +81,7 @@ typedef void (*DjiLiveview_H264Callback)(E_DjiLiveViewCameraPosition position, c
/* Exported functions --------------------------------------------------------*/
/**
* @brief Initialize the liveview module.
* @note The interface initialization needs to be after DjiCore_Init.
* @note Must be called after DjiCore_Init.
* @return Execution result.
*/
T_DjiReturnCode DjiLiveview_Init(void);
@ -90,27 +93,27 @@ T_DjiReturnCode DjiLiveview_Init(void);
T_DjiReturnCode DjiLiveview_Deinit(void);
/**
* @brief Start the FPV or Camera H264 Stream by selected position.
* @param position: point out which camera to output the H264 stream
* @param source: point out which sub camera to output the H264 stream
* @param callback: callback function that is called in a callback thread when a new h264 frame is received
* @brief Start the FPV or camera H264 stream from the specified position.
* @param position: Camera position for the H264 stream output.
* @param source: sub-camera source for the H264 stream output.
* @param callback: Callback function in a callback thread when a new h264 frame is received
* @return Execution result.
*/
T_DjiReturnCode DjiLiveview_StartH264Stream(E_DjiLiveViewCameraPosition position, E_DjiLiveViewCameraSource source,
DjiLiveview_H264Callback callback);
/**
* @brief Stop the FPV or Camera H264 Stream by selected position.
* @param position: point out which camera to output the H264 stream
* @param source: point out which sub camera to output the H264 stream
* @brief Stop the FPV or Camera H264 Stream from the specified position.
* @param position: Camera position for the H264 stream output.
* @param source: sub-camera source for the H264 stream output.
* @return Execution result.
*/
T_DjiReturnCode DjiLiveview_StopH264Stream(E_DjiLiveViewCameraPosition position, E_DjiLiveViewCameraSource source);
/**
* @brief Request the intraframe Frame of Camera H264 Stream by selected position.
* @param position: point out which camera to output the H264 stream
* @param source: point out which sub camera to output the H264 stream
* @brief Request the intraframe Frame of camera H264 stream from the specified position.
* @param position: Camera position for the H264 stream output.
* @param source: sub-camera source for the H264 stream output.
* @return Execution result.
*/
T_DjiReturnCode DjiLiveview_RequestIntraframeFrameData(E_DjiLiveViewCameraPosition position,

View File

@ -39,6 +39,14 @@ extern "C" {
/* Exported constants --------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief Positioning rtcm data type.
*/
typedef enum {
DJI_POSITIONING_RTCM_DATA_TYPE_RTK_ON_AIRCRAFT = 0,
DJI_POSITIONING_RTCM_DATA_TYPE_RTK_BASE_STATION = 1,
} E_DjiPositioningRtcmDataType;
/**
* @brief Data structure that describes a positioning event.
*/
@ -84,6 +92,15 @@ typedef struct {
T_DjiPositioningPositionStandardDeviation targetPointPositionStandardDeviation; /*!< Specifies position standard deviation of target points. */
} T_DjiPositioningPositionInfo;
/**
* @brief Prototype of callback function used to receive the rtk rtcm raw data.
* @param index: the index of rtcm data package.
* @param data: pointer to receive rtk rtcm data from aircraft.
* @param dataLen: receive data length of rtcm data from aircraft.
* @return Execution result.
*/
typedef T_DjiReturnCode (*DjiReceiveRtkRtcmDataCallback)(uint8_t index, const uint8_t *data, uint16_t dataLen);
/* Exported functions --------------------------------------------------------*/
/**
* @brief Initialise positioning module in blocking mode. User should call this function before all other positioning
@ -128,6 +145,15 @@ void DjiPositioning_SetTaskIndex(uint8_t index);
T_DjiReturnCode DjiPositioning_GetPositionInformationSync(uint8_t eventCount, T_DjiPositioningEventInfo *eventInfo,
T_DjiPositioningPositionInfo *positionInfo);
/**
* @brief Register callback function used to receive rtk rtcm raw data by data type.
* @note The callback function will be called after registering. The call frequency depends on the number of satellites.
* @param callback: pointer to the callback function.
* @return Execution result.
*/
T_DjiReturnCode DjiPositioning_RegReceiveRtcmDataCallback(E_DjiPositioningRtcmDataType dataType,
DjiReceiveRtkRtcmDataCallback callback);
#ifdef __cplusplus
}
#endif

View File

@ -42,11 +42,11 @@ extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
#define DJI_PI (3.14159265358979323846f)
#define DJI_FILE_NAME_SIZE_MAX 256
#define DJI_FILE_PATH_SIZE_MAX (DJI_FILE_NAME_SIZE_MAX + 256)
#define DJI_IP_ADDR_STR_SIZE_MAX 15
#define DJI_MD5_BUFFER_LEN 16
#define DJI_PI (3.14159265358979323846f)
#define DJI_FILE_NAME_SIZE_MAX 256
#define DJI_FILE_PATH_SIZE_MAX (DJI_FILE_NAME_SIZE_MAX + 256)
#define DJI_IP_ADDR_STR_SIZE_MAX 15
#define DJI_MD5_BUFFER_LEN 16
#define DJI_SUBSCRIPTION_MODULE_INDEX_OFFSET 24u
#define DJI_SUBSCRIPTION_MODULE_INDEX_MASK 0xFF000000u
@ -54,9 +54,9 @@ extern "C" {
#define DJI_SUBSCRIPTION_TOPIC_CODE_MASK 0x00FFFFFFu
#define DJI_DATA_SUBSCRIPTION_TOPIC(subscriptionModule, topicCode) \
(uint32_t)\
(((((uint32_t)(subscriptionModule)) << (DJI_SUBSCRIPTION_MODULE_INDEX_OFFSET)) & (DJI_SUBSCRIPTION_MODULE_INDEX_MASK)) | \
((((uint32_t)(topicCode)) << (DJI_SUBSCRIPTION_TOPIC_CODE_OFFSET)) & (DJI_SUBSCRIPTION_TOPIC_CODE_MASK)))
(uint32_t)\
(((((uint32_t)(subscriptionModule)) << (DJI_SUBSCRIPTION_MODULE_INDEX_OFFSET)) & (DJI_SUBSCRIPTION_MODULE_INDEX_MASK)) | \
((((uint32_t)(topicCode)) << (DJI_SUBSCRIPTION_TOPIC_CODE_OFFSET)) & (DJI_SUBSCRIPTION_TOPIC_CODE_MASK)))
/**
* @brief Type define double as dji_f64_t.
@ -73,70 +73,103 @@ typedef float dji_f32_t;
typedef uint64_t T_DjiReturnCode;
typedef enum {
DJI_MOUNT_POSITION_TYPE_UNKNOWN = 0,
DJI_MOUNT_POSITION_TYPE_PAYLOAD_PORT = 1,
DJI_MOUNT_POSITION_TYPE_EXTENSION_PORT = 2
DJI_MOUNT_POSITION_TYPE_UNKNOWN = 0,
DJI_MOUNT_POSITION_TYPE_PAYLOAD_PORT = 1,
DJI_MOUNT_POSITION_TYPE_EXTENSION_PORT = 2,
DJI_MOUNT_POSITION_TYPE_EXTENSION_LITE_PORT = 3
} E_DjiMountPositionType;
typedef enum {
DJI_MOUNT_POSITION_UNKNOWN = 0,
DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1 = 1,
DJI_MOUNT_POSITION_PAYLOAD_PORT_NO2 = 2,
DJI_MOUNT_POSITION_PAYLOAD_PORT_NO3 = 3,
DJI_MOUNT_POSITION_EXTENSION_PORT = 4,
DJI_MOUNT_POSITION_UNKNOWN = 0,
DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1 = 1,
DJI_MOUNT_POSITION_PAYLOAD_PORT_NO2 = 2,
DJI_MOUNT_POSITION_PAYLOAD_PORT_NO3 = 3,
DJI_MOUNT_POSITION_EXTENSION_PORT = 4,
DJI_MOUNT_POSITION_EXTENSION_LITE_PORT = 5,
} E_DjiMountPosition;
typedef enum {
DJI_AIRCRAFT_SERIES_UNKNOWN = 0,
DJI_AIRCRAFT_SERIES_M200_V2 = 1,
DJI_AIRCRAFT_SERIES_M300 = 2,
DJI_AIRCRAFT_SERIES_M30 = 3,
DJI_AIRCRAFT_SERIES_M3 = 4,
DJI_AIRCRAFT_SERIES_M350 = 5,
DJI_AIRCRAFT_SERIES_UNKNOWN = 0,
DJI_AIRCRAFT_SERIES_M200_V2 = 1,
DJI_AIRCRAFT_SERIES_M300 = 2,
DJI_AIRCRAFT_SERIES_M30 = 3,
DJI_AIRCRAFT_SERIES_M3 = 4,
DJI_AIRCRAFT_SERIES_M350 = 5,
DJI_AIRCRAFT_SERIES_M3D = 6,
DJI_AIRCRAFT_SERIES_FC30 = 7,
} E_DjiAircraftSeries;
typedef enum {
DJI_AIRCRAFT_TYPE_UNKNOWN = 0, /*!< Aircraft type is unknown. */
DJI_AIRCRAFT_TYPE_M200_V2 = 44, /*!< Aircraft type is Matrice 200 V2. */
DJI_AIRCRAFT_TYPE_M210_V2 = 45, /*!< Aircraft type is Matrice 220 V2. */
DJI_AIRCRAFT_TYPE_M210RTK_V2 = 46, /*!< Aircraft type is Matrice 210 RTK V2. */
DJI_AIRCRAFT_TYPE_M300_RTK = 60, /*!< Aircraft type is Matrice 300 RTK. */
DJI_AIRCRAFT_TYPE_M30 = 67, /*!< Aircraft type is Matrice 30. */
DJI_AIRCRAFT_TYPE_M30T = 68, /*!< Aircraft type is Matrice 30T. */
DJI_AIRCRAFT_TYPE_M3E = 77, /*!< Aircraft type is Mavic 3E. */
DJI_AIRCRAFT_TYPE_M3T = 79, /*!< Aircraft type is Mavic 3T. */
DJI_AIRCRAFT_TYPE_M350_RTK = 89, /*!< Aircraft type is Matrice 350 RTK. */
DJI_AIRCRAFT_TYPE_UNKNOWN = 0, /*!< Aircraft type is unknown. */
DJI_AIRCRAFT_TYPE_M200_V2 = 44, /*!< Aircraft type is Matrice 200 V2. */
DJI_AIRCRAFT_TYPE_M210_V2 = 45, /*!< Aircraft type is Matrice 220 V2. */
DJI_AIRCRAFT_TYPE_M210RTK_V2 = 46, /*!< Aircraft type is Matrice 210 RTK V2. */
DJI_AIRCRAFT_TYPE_M300_RTK = 60, /*!< Aircraft type is Matrice 300 RTK. */
DJI_AIRCRAFT_TYPE_M30 = 67, /*!< Aircraft type is Matrice 30. */
DJI_AIRCRAFT_TYPE_M30T = 68, /*!< Aircraft type is Matrice 30T. */
DJI_AIRCRAFT_TYPE_M3E = 77, /*!< Aircraft type is Mavic 3E. */
DJI_AIRCRAFT_TYPE_FC30 = 78, /* !<Aircraft type is FlyCart 30> */
DJI_AIRCRAFT_TYPE_M3T = 79, /*!< Aircraft type is Mavic 3T. */
DJI_AIRCRAFT_TYPE_M350_RTK = 89, /*!< Aircraft type is Matrice 350 RTK. */
DJI_AIRCRAFT_TYPE_M3D = 91, /*!< Aircraft type is Matrice 3D. */
DJI_AIRCRAFT_TYPE_M3TD = 93, /*!< Aircraft type is Matrice 3TD. */
} E_DjiAircraftType;
/**
* @brief Camera type.
*/
typedef enum {
DJI_CAMERA_TYPE_UNKNOWN = 0, /*!< Camera type is unknown. */
DJI_CAMERA_TYPE_Z30 = 20, /*!< Camera type is Z30. */
DJI_CAMERA_TYPE_XT2 = 26, /*!< Camera type is XT2. */
DJI_CAMERA_TYPE_PSDK = 31, /*!< Camera type is third party camera based on Payload SDK. */
DJI_CAMERA_TYPE_XTS = 41, /*!< Camera type is XT S. */
DJI_CAMERA_TYPE_H20 = 42, /*!< Camera type is H20. */
DJI_CAMERA_TYPE_H20T = 43, /*!< Camera type is H20T. */
DJI_CAMERA_TYPE_H20N = 61, /*!< Camera type is H20N. */
DJI_CAMERA_TYPE_P1 = 50, /*!< Camera type is P1. */
DJI_CAMERA_TYPE_UNKNOWN = 0, /*!< Camera type is unknown. */
DJI_CAMERA_TYPE_Z30 = 20, /*!< Camera type is Z30. */
DJI_CAMERA_TYPE_XT2 = 26, /*!< Camera type is XT2. */
DJI_CAMERA_TYPE_PSDK = 31, /*!< Camera type is third party camera based on Payload SDK. */
DJI_CAMERA_TYPE_XTS = 41, /*!< Camera type is XT S. */
DJI_CAMERA_TYPE_H20 = 42, /*!< Camera type is H20. */
DJI_CAMERA_TYPE_H20T = 43, /*!< Camera type is H20T. */
DJI_CAMERA_TYPE_H20N = 61, /*!< Camera type is H20N. */
DJI_CAMERA_TYPE_P1 = 50, /*!< Camera type is P1. */
DJI_CAMERA_TYPE_L1, /*!< Camera type is L1. */
DJI_CAMERA_TYPE_M30, /*!< Camera type is M30. */
DJI_CAMERA_TYPE_M30T, /*!< Camera type is M30T. */
DJI_CAMERA_TYPE_M3E, /*!< Camera type is M3E. */
DJI_CAMERA_TYPE_M3T, /*!< Camera type is M3T. */
DJI_CAMERA_TYPE_L2 = 84, /*!< Camera type is L2. */
DJI_CAMERA_TYPE_M30 = 52, /*!< Camera type is M30. */
DJI_CAMERA_TYPE_M30T = 53, /*!< Camera type is M30T. */
DJI_CAMERA_TYPE_M3E = 66, /*!< Camera type is M3E. */
DJI_CAMERA_TYPE_M3T = 67, /*!< Camera type is M3T. */
DJI_CAMERA_TYPE_M3D = 80, /*!< Camera type is Matrice 3D. */
DJI_CAMERA_TYPE_M3TD = 81, /*!< Camera type is Matrice 3TD. */
DJI_CAMERA_TYPE_H30 = 82, /*!< Camera type is H30. */
DJI_CAMERA_TYPE_H30T = 83, /*!< Camera type is H30T. */
} E_DjiCameraType;
/**
* @brief Camera supported media file subtype.
*/
typedef enum
{
DJI_DOWNLOAD_FILE_ORG = 0, /*!< Media sub file origin data type. */
DJI_DOWNLOAD_FILE_LDR = 21, /*!< Media sub file cloud point raw data type. */
DJI_DOWNLOAD_FILE_SIG = 22, /*!< Media sub file point cloud signature type. */
DJI_DOWNLOAD_FILE_RTK = 23, /*!< Media sub file point cloud real-time kinematic type. */
DJI_DOWNLOAD_FILE_CLC = 25, /*!< Media sub file radar-camera external reference type. */
DJI_DOWNLOAD_FILE_CLI = 26, /*!< Media sub file radar-IMU external reference type. */
DJI_DOWNLOAD_FILE_IMU = 27, /*!< Media sub file IMU data type. */
DJI_DOWNLOAD_FILE_RTL = 28, /*!< Media sub file RTK boom data type. */
DJI_DOWNLOAD_FILE_RTB = 29, /*!< Media sub file RTK base station data type. */
DJI_DOWNLOAD_FILE_RTS = 30, /*!< Media sub file RTK secondary antenna data type. */
DJI_DOWNLOAD_FILE_RPOS = 31, /*!< Media sub file real-time fusion of attitude and position data type. */
} E_DjiCameraMediaFileSubType;
/**
* @brief Camera supported media file type.
*/
typedef enum {
DJI_CAMERA_FILE_TYPE_JPEG = 0, /*!< Media file JPEG type. */
DJI_CAMERA_FILE_TYPE_DNG = 1, /*!< Media file DNG type. */
DJI_CAMERA_FILE_TYPE_MOV = 2, /*!< Media file MOV type. */
DJI_CAMERA_FILE_TYPE_MP4 = 3, /*!< Media file MP4 type. */
DJI_CAMERA_FILE_TYPE_UNKNOWN = 255, /*!< Media file unknown type. */
DJI_CAMERA_FILE_TYPE_JPEG = 0, /*!< Media file JPEG type. */
DJI_CAMERA_FILE_TYPE_DNG = 1, /*!< Media file DNG type. */
DJI_CAMERA_FILE_TYPE_MOV = 2, /*!< Media file MOV type. */
DJI_CAMERA_FILE_TYPE_MP4 = 3, /*!< Media file MP4 type. */
DJI_CAMERA_FILE_TYPE_TIFF = 5, /*!< Media file TIFF type. */
DJI_CAMERA_FILE_TYPE_LDRT = 24, /*!< Media file LDRT type. */
DJI_CAMERA_FILE_TYPE_RPT = 25, /*!< Media file RPT type. */
DJI_CAMERA_FILE_TYPE_UNKNOWN = 255, /*!< Media file unknown type. */
} E_DjiCameraMediaFileType;
/**
@ -152,60 +185,58 @@ typedef struct {
* @brief Gimbal work mode, specifies how gimbal follow aircraft movement.
*/
typedef enum {
DJI_GIMBAL_MODE_FREE = 0, /*!< Free mode, fix gimbal attitude in the ground coordinate, ignoring movement of aircraft. */
DJI_GIMBAL_MODE_FPV = 1, /*!< FPV (First Person View) mode, only control roll and yaw angle of gimbal in the ground coordinate to follow aircraft. */
DJI_GIMBAL_MODE_YAW_FOLLOW = 2, /*!< Yaw follow mode, only control yaw angle of gimbal in the ground coordinate to follow aircraft. */
DJI_GIMBAL_MODE_FREE = 0, /*!< Free mode, fix gimbal attitude in the ground coordinate, ignoring movement of aircraft. */
DJI_GIMBAL_MODE_FPV = 1, /*!< FPV (First Person View) mode, only control roll and yaw angle of gimbal in the ground coordinate to follow aircraft. */
DJI_GIMBAL_MODE_YAW_FOLLOW = 2, /*!< Yaw follow mode, only control yaw angle of gimbal in the ground coordinate to follow aircraft. */
} E_DjiGimbalMode;
/**
* @brief Gimbal rotation mode, specifies control style.
*/
typedef enum {
DJI_GIMBAL_ROTATION_MODE_RELATIVE_ANGLE = 0, /*!< Relative angle rotation mode, represents rotating gimbal specified angles based on current angles. */
DJI_GIMBAL_ROTATION_MODE_ABSOLUTE_ANGLE = 1, /*!< Absolute angle rotation mode, represents rotating gimbal to specified angles in the ground coordinate. */
DJI_GIMBAL_ROTATION_MODE_SPEED = 2, /*!< Speed rotation mode, specifies rotation speed of gimbal in the ground coordinate. */
DJI_GIMBAL_ROTATION_MODE_RELATIVE_ANGLE = 0, /*!< Relative angle rotation mode, represents rotating gimbal specified angles based on current angles. */
DJI_GIMBAL_ROTATION_MODE_ABSOLUTE_ANGLE = 1, /*!< Absolute angle rotation mode, represents rotating gimbal to specified angles in the ground coordinate. */
DJI_GIMBAL_ROTATION_MODE_SPEED = 2, /*!< Speed rotation mode, specifies rotation speed of gimbal in the ground coordinate. */
} E_DjiGimbalRotationMode;
/**
* @brief Mobile APP system language.
*/
typedef enum {
DJI_MOBILE_APP_LANGUAGE_UNKNOWN = 255, /*!< The system language of the mobile app is unknown */
DJI_MOBILE_APP_LANGUAGE_ENGLISH = 0, /*!< The system language of the mobile app is English */
DJI_MOBILE_APP_LANGUAGE_CHINESE = 1, /*!< The system language of the mobile app is Chinese */
DJI_MOBILE_APP_LANGUAGE_JAPANESE = 2, /*!< The system language of the mobile app is Japanese */
DJI_MOBILE_APP_LANGUAGE_FRENCH = 3, /*!< The system language of the mobile app is French */
DJI_MOBILE_APP_LANGUAGE_UNKNOWN = 255, /*!< The system language of the mobile app is unknown */
DJI_MOBILE_APP_LANGUAGE_ENGLISH = 0, /*!< The system language of the mobile app is English */
DJI_MOBILE_APP_LANGUAGE_CHINESE = 1, /*!< The system language of the mobile app is Chinese */
DJI_MOBILE_APP_LANGUAGE_JAPANESE = 2, /*!< The system language of the mobile app is Japanese */
DJI_MOBILE_APP_LANGUAGE_FRENCH = 3, /*!< The system language of the mobile app is French */
} E_DjiMobileAppLanguage;
/**
* @brief Mobile APP screen size type.
*/
typedef enum {
DJI_MOBILE_APP_SCREEN_TYPE_UNKNOWN = 255, /*!< Mobile APP screen type is unknown. */
DJI_MOBILE_APP_SCREEN_TYPE_BIG_SCREEN = 0, /*!< The big screen of mobile device refers to a screen
* size greater than or equal to 6 inches. */
DJI_MOBILE_APP_SCREEN_TYPE_LITTLE_SCREEN = 1, /*!< The little screen of mobile device refers to a
* screen size less than 6 inches. */
DJI_MOBILE_APP_SCREEN_TYPE_UNKNOWN = 255, /*!< Mobile APP screen type is unknown. */
DJI_MOBILE_APP_SCREEN_TYPE_BIG_SCREEN = 0, /*!< Screen size is 6 inches or larger. */
DJI_MOBILE_APP_SCREEN_TYPE_LITTLE_SCREEN = 1, /*!< Screen size is less than 6 inches. */
} E_DjiMobileAppScreenType;
/**
* @brief Subscription frequency type.
*/
typedef enum {
DJI_DATA_SUBSCRIPTION_TOPIC_1_HZ = 1,
DJI_DATA_SUBSCRIPTION_TOPIC_5_HZ = 5,
DJI_DATA_SUBSCRIPTION_TOPIC_10_HZ = 10,
DJI_DATA_SUBSCRIPTION_TOPIC_50_HZ = 50,
DJI_DATA_SUBSCRIPTION_TOPIC_100_HZ = 100,
DJI_DATA_SUBSCRIPTION_TOPIC_200_HZ = 200,
DJI_DATA_SUBSCRIPTION_TOPIC_400_HZ = 400,
DJI_DATA_SUBSCRIPTION_TOPIC_1_HZ = 1,
DJI_DATA_SUBSCRIPTION_TOPIC_5_HZ = 5,
DJI_DATA_SUBSCRIPTION_TOPIC_10_HZ = 10,
DJI_DATA_SUBSCRIPTION_TOPIC_50_HZ = 50,
DJI_DATA_SUBSCRIPTION_TOPIC_100_HZ = 100,
DJI_DATA_SUBSCRIPTION_TOPIC_200_HZ = 200,
DJI_DATA_SUBSCRIPTION_TOPIC_400_HZ = 400,
} E_DjiDataSubscriptionTopicFreq;
/**
* @brief DJI module enum for defining data subscription module.
*/
typedef enum {
DJI_DATA_SUBSCRIPTION_MODULE_FC = 0,
DJI_DATA_SUBSCRIPTION_MODULE_FC = 0,
DJI_DATA_SUBSCRIPTION_MODULE_CAMERA,
DJI_DATA_SUBSCRIPTION_MODULE_ERROR,
} E_DjiDataSubscriptionModule;
@ -214,85 +245,77 @@ typedef enum {
* @brief SDK adapter type.
*/
typedef enum {
DJI_SDK_ADAPTER_TYPE_UNKNOWN = 0, /*!< SDK adapter type is unknown. */
DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 = 1, /*!< SDK adapter type is Skyport V2. */
DJI_SDK_ADAPTER_TYPE_XPORT = 2, /*!< SDK adapter type is X-Port. */
DJI_SDK_ADAPTER_TYPE_NONE = 3, /*!< don't have any adapter outside */
DJI_SDK_ADAPTER_TYPE_UNKNOWN = 0, /*!< SDK adapter type is unknown. */
DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 = 1, /*!< SDK adapter type is Skyport V2. */
DJI_SDK_ADAPTER_TYPE_XPORT = 2, /*!< SDK adapter type is X-Port. */
DJI_SDK_ADAPTER_TYPE_NONE = 3, /*!< No external adapter is connected. */
} E_DjiSdkAdapterType;
typedef enum {
DJI_CHANNEL_ADDRESS_UNKNOWN = 0,
DJI_CHANNEL_ADDRESS_UNKNOWN = 0,
DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO1,
DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO2,
DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO3,
DJI_CHANNEL_ADDRESS_EXTENSION_PORT,
DJI_CHANNEL_ADDRESS_MASTER_RC_APP,
DJI_CHANNEL_ADDRESS_SLAVE_RC_APP,
DJI_CHANNEL_ADDRESS_CLOUD_API,
} E_DjiChannelAddress;
/**
* @brief Camera focus target point when in focus mode.
*/
typedef struct {
dji_f32_t focusX; /*!< Specifies horizontal zone coordinate. This parameter is between 0 and 1.
The point [0.0, 0.0] represents the top-left angle of the screen.*/
dji_f32_t focusY; /*!< Specifies vertical zone coordinate. This parameter is between 0 and 1. */
dji_f32_t focusX; /*!< Specifies the horizontal coordinate within the zone. Range: 0 to 1.
The point [0.0, 0.0] represents the top-left corner of the screen.*/
dji_f32_t focusY; /*!< Specifies vertical zone coordinate. Range: 0 to 1. */
} T_DjiCameraPointInScreen;
/**
* @brief Camera time interval settings when in interval shootPhoto mode.
* @brief Camera time interval settings for interval shoot-photo mode.
*/
typedef struct {
uint8_t captureCount; /*!< Specifies the total capture count of interval settings.
* 0:reserve 1~254:number 255:keep capturing till stop */
* 0: reserved, 1-254: specific number, 255: continuous capture until stopped. */
uint16_t timeIntervalSeconds; /*!< Specifies the interval time between two captures, unit: s*/
} T_DjiCameraPhotoTimeIntervalSettings;
/**
* @brief Camera zoom speed.
* @brief Camera zoom speeds.
*/
typedef enum {
DJI_CAMERA_ZOOM_SPEED_SLOWEST = 72, /*!< Lens zooms in slowest speed. */
DJI_CAMERA_ZOOM_SPEED_SLOW = 73, /*!< Lens zooms in slow speed. */
DJI_CAMERA_ZOOM_SPEED_MODERATELY_SLOW = 74, /*!< Lens zooms in speed slightly slower than normal speed. */
DJI_CAMERA_ZOOM_SPEED_NORMAL = 75, /*!< Lens zooms in normal speed. */
DJI_CAMERA_ZOOM_SPEED_MODERATELY_FAST = 76, /*!< Lens zooms very in speed slightly faster than normal speed. */
DJI_CAMERA_ZOOM_SPEED_FAST = 77, /*!< Lens zooms very in fast speed. */
DJI_CAMERA_ZOOM_SPEED_FASTEST = 78, /*!< Lens zooms very in fastest speed. */
DJI_CAMERA_ZOOM_SPEED_SLOWEST = 72, /*!< Slowest zoom speed. */
DJI_CAMERA_ZOOM_SPEED_SLOW = 73, /*!< Slow zoom speed. */
DJI_CAMERA_ZOOM_SPEED_MODERATELY_SLOW = 74, /*!< Slightly slower than normal zoom speed. */
DJI_CAMERA_ZOOM_SPEED_NORMAL = 75, /*!< Normal zoom speed. */
DJI_CAMERA_ZOOM_SPEED_MODERATELY_FAST = 76, /*!< Slightly faster than normal zoom speed. */
DJI_CAMERA_ZOOM_SPEED_FAST = 77, /*!< Fast zoom speed. */
DJI_CAMERA_ZOOM_SPEED_FASTEST = 78, /*!< Fastest zoom speed. */
} E_DjiCameraZoomSpeed;
typedef enum {
/*! The number of pictures to continuously take each time in BURST mode is 2
*/
DJI_CAMERA_BURST_COUNT_2 = 2,
/*! The number of pictures to continuously take each time in BURST mode is 3
*/
DJI_CAMERA_BURST_COUNT_3 = 3,
/*! The number of pictures to continuously take each time in BURST mode is 5
*/
DJI_CAMERA_BURST_COUNT_5 = 5,
/*! The number of pictures to continuously take each time in BURST mode is 7
*/
DJI_CAMERA_BURST_COUNT_7 = 7,
/*! The number of pictures to continuously take at one time in BURST mode is
* 10, Only supported by X4S camera, X5S camera and Phantom 4 Pro camera.
*/
DJI_CAMERA_BURST_COUNT_10 = 10,
/*! The number of pictures to continuously take at one time in BURST mode is
* 14, Only supported by X4S camera, X5S camera and Phantom 4 Pro camera.
*/
DJI_CAMERA_BURST_COUNT_14 = 14,
/*! The camera burst shoot count value is unknown.
*/
DJI_CAMERA_BURST_COUNT_KNOWN = 0xFF,
/*! The burst mode can capture 2 pictures per trigger. */
DJI_CAMERA_BURST_COUNT_2 = 2,
/*! The burst mode can capture 3 pictures per trigger. */
DJI_CAMERA_BURST_COUNT_3 = 3,
/*! The burst mode can capture 5 pictures per trigger. */
DJI_CAMERA_BURST_COUNT_5 = 5,
/*! The burst mode can capture 7 pictures per trigger. */
DJI_CAMERA_BURST_COUNT_7 = 7,
/*! Supports capturing 10 pictures per trigger, only supported by X4S, X5S cameras, and Phantom 4 Pro. */
DJI_CAMERA_BURST_COUNT_10 = 10,
/*! Supports capturing 14 pictures per trigger, only supported by X4S, X5S cameras, and Phantom 4 Pro. */
DJI_CAMERA_BURST_COUNT_14 = 14,
/*! Unknown burst count. */
DJI_CAMERA_BURST_COUNT_KNOWN = 0xFF,
} E_DjiCameraBurstCount;
/**
* @brief Camera zoom direction.
*/
typedef enum {
DJI_CAMERA_ZOOM_DIRECTION_OUT = 0, /*!< The lens moves in the far direction, the zoom factor becomes smaller. */
DJI_CAMERA_ZOOM_DIRECTION_IN = 1, /*!< The lens moves in the near direction, the zoom factor becomes larger. */
DJI_CAMERA_ZOOM_DIRECTION_OUT = 0, /*!< Zooms out, reducing the zoom factor. */
DJI_CAMERA_ZOOM_DIRECTION_IN = 1, /*!< Zooms in, increasing the zoom factor. */
} E_DjiCameraZoomDirection;
#pragma pack (1)
@ -320,55 +343,70 @@ typedef struct {
bool busyState;
} T_DjiDataChannelState;
typedef struct Vector3d {
int32_t x; /*!< Specifies int32 value of x for vector. */
int32_t y; /*!< Specifies int32 value of y for vector. */
int32_t z; /*!< Specifies int32 value of z for vector. */
/**
* @brief Represents a vector using int32 coordinates.
*/
typedef struct Vector3d{
int32_t x; /*!< X-coordinate of the vector. */
int32_t y; /*!< Y-coordinate of the vector. */
int32_t z; /*!< Z-coordinate of the vector. */
} T_DjiVector3d;
typedef struct Vector3f {
dji_f32_t x; /*!< Specifies float value of x for vector. */
dji_f32_t y; /*!< Specifies float value of y for vector. */
dji_f32_t z; /*!< Specifies float value of z for vector. */
/**
* @brief Represents a vector using floating-point coordinates.
*/
typedef struct Vector3f{
dji_f32_t x; /*!< X-coordinate of the vector. */
dji_f32_t y; /*!< Y-coordinate of the vector. */
dji_f32_t z; /*!< Z-coordinate of the vector. */
} T_DjiVector3f;
/**
* @brief Represents an attitude using int32 values for pitch, roll, and yaw.
*/
typedef struct {
int32_t pitch; /*!< Specifies int32 value of pitch for attitude. */
int32_t roll; /*!< Specifies int32 value of roll for attitude */
int32_t yaw; /*!< Specifies int32 value of yaw for attitude */
int32_t pitch; /*!< Pitch angle in degrees. */
int32_t roll; /*!< Roll angle in degrees. */
int32_t yaw; /*!< Yaw angle in degrees. */
} T_DjiAttitude3d;
/**
* @brief Represents an attitude using floating-point values for pitch, roll, and yaw.
*/
typedef struct {
dji_f32_t pitch; /*!< Specifies float value of pitch for attitude. */
dji_f32_t roll; /*!< Specifies float value of roll for attitude */
dji_f32_t yaw; /*!< Specifies float value of yaw for attitude */
dji_f32_t pitch; /*!< Pitch angle in degrees. */
dji_f32_t roll; /*!< Roll angle in degrees. */
dji_f32_t yaw; /*!< Yaw angle in degrees. */
} T_DjiAttitude3f;
/**
* @brief Represents a quaternion, when converted to a rotation matrix or Euler angles.
*/
typedef struct {
dji_f32_t q0; /*!< w, when converted to a rotation matrix or Euler angles. */
dji_f32_t q1; /*!< x, when converted to a rotation matrix or Euler angles. */
dji_f32_t q2; /*!< y, when converted to a rotation matrix or Euler angles. */
dji_f32_t q3; /*!< z, when converted to a rotation matrix or Euler angles. */
dji_f32_t q0; /*!< Quaternion component w. */
dji_f32_t q1; /*!< Quaternion component x. */
dji_f32_t q2; /*!< Quaternion component y. */
dji_f32_t q3; /*!< Quaternion component z. */
} T_DjiQuaternion4f;
/**
* @brief Timestamp data structure.
*/
typedef struct {
uint32_t millisecond; /*!< Millisecond. */
uint32_t microsecond; /*!< Microsecond. */
uint32_t millisecond;
uint32_t microsecond;
} T_DjiDataTimestamp;
/**
* @brief The firmware version of payload.
* @note If majorVersion = AA, minorVersion = BB, modifyVersion = CC, debugVersion = DD, The version show in
* terminal APP is AA.BB.CC.DD
* @note The firmware version is displayed as AA.BB.CC.DD where AA is majorVersion,
* BB is minorVersion, CC is modifyVersion, and DD is debugVersion.
*/
typedef struct {
uint8_t majorVersion; /*!< The major version of firmware, the range is 0 ~ 99. */
uint8_t minorVersion; /*!< The minor version of firmware, the range is 0 ~ 99. */
uint8_t modifyVersion; /*!< The modify version of firmware, the range is 0 ~ 99. */
uint8_t debugVersion; /*!< The debug version of firmware, the range is 0 ~ 99. */
uint8_t majorVersion; /*!< Major version number, ranging from 0 to 99. */
uint8_t minorVersion; /*!< Minor version number, ranging from 0 to 99. */
uint8_t modifyVersion; /*!< Modification version number, ranging from 0 to 99. */
uint8_t debugVersion; /*!< Debug version number, ranging from 0 to 99. */
} T_DjiFirmwareVersion;
#pragma pack ()

View File

@ -34,10 +34,10 @@ extern "C" {
/* Exported constants --------------------------------------------------------*/
#define DJI_VERSION_MAJOR 3 /*!< DJI SDK major version num, when have incompatible API changes. Range from 0 to 99. */
#define DJI_VERSION_MINOR 5 /*!< DJI SDK minor version num, when add functionality in a backwards compatible manner changes. Range from 0 to 99. */
#define DJI_VERSION_MODIFY 0 /*!< DJI SDK modify version num, when have backwards compatible bug fixes changes. Range from 0 to 99. */
#define DJI_VERSION_MINOR 9 /*!< DJI SDK minor version num, when add functionality in a backwards compatible manner changes. Range from 0 to 99. */
#define DJI_VERSION_MODIFY 1 /*!< DJI SDK modify version num, when have backwards compatible bug fixes changes. Range from 0 to 99. */
#define DJI_VERSION_BETA 0 /*!< DJI SDK version beta info, release version will be 0, when beta version release changes. Range from 0 to 255. */
#define DJI_VERSION_BUILD 1764 /*!< DJI SDK version build info, when jenkins trigger build changes. Range from 0 to 65535. */
#define DJI_VERSION_BUILD 2090 /*!< DJI SDK version build info, when jenkins trigger build changes. Range from 0 to 65535. */
/* Exported types ------------------------------------------------------------*/

View File

@ -36,6 +36,10 @@ extern "C" {
/* Exported constants --------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/**
* @brief Type define dji_f32_t as T_DjiWaypointV2GlobalCruiseSpeed.
* @details Type used for global cruise speed of waypoint mission, unit: m/s.
*/
typedef dji_f32_t T_DjiWaypointV2GlobalCruiseSpeed;
/**
@ -184,7 +188,7 @@ typedef enum {
* using ``DJIWaypointV2_pointOfInterest`` setting point of interest coordiate and ``DJIWaypointV2_pointOfInterestAltitude``
* setting point of interset altitute.
*/
DJI_WAYPOINT_V2_HEADING_TOWARDS_POINT_OD_INTEREST,
DJI_WAYPOINT_V2_HEADING_TOWARDS_POINT_OF_INTEREST,
/**
* The aircraft's heading rotate simultaneously with its gimbal's yaw.
@ -340,6 +344,8 @@ typedef struct {
* will fly backwards to previous waypoints. When it reaches the first waypoint, it
* will then hover in place until a positive speed is applied. "maxFlightSpeed" has
* a range of [2,15] m/s.
*
* unit: m/s
*/
dji_f32_t maxFlightSpeed;
@ -355,6 +361,8 @@ typedef struct {
* joystick. In flight controller firmware 3.2.10.0 or above, different speeds
* between individual waypoints can also be set in waypoint objects which will
* overwrite "autoFlightSpeed".
*
* unit: m/s.
*/
dji_f32_t autoFlightSpeed;
} T_DjiWaypointV2;
@ -1089,6 +1097,7 @@ typedef struct {
* negative, then the aircraft will fly backwards to previous waypoints. When it
* reaches the first waypoint, it will then hover in place until a positive speed
* is applied. `maxFlightSpeed` has a range of [2,15] m/s.
*
* unit: m/s
*/
dji_f32_t maxFlightSpeed;
@ -1103,6 +1112,7 @@ typedef struct {
* `autoFlightSpeed` <0 and the aircraft is at the first waypoint, the aircraft
* will hover in place until the speed is made positive by the remote controller
* joystick.
*
* unit: m/s
*/
dji_f32_t autoFlightSpeed;