M350b版本
This commit is contained in:
@ -66,6 +66,14 @@ typedef struct {
|
||||
uint8_t majorVersion;
|
||||
} T_DjiAircraftVersion;
|
||||
|
||||
/**
|
||||
* @brief enhanced transmission state.
|
||||
*/
|
||||
typedef enum {
|
||||
DJI_ENHANCEED_TRANSMISSION_STATE_DISABLED = 0, /**< Mobile app image transmission setting, Enhanced transmission disabled */
|
||||
DJI_ENHANCEED_TRANSMISSION_STATE_ENABLED = 3, /**< Mobile app image transmission setting, Enhanced transmission enabled. */
|
||||
} E_DjiEnhancedTransmissionState;
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Basic information about the aircraft system, including aircraft type and DJI adapter type.
|
||||
@ -97,6 +105,13 @@ T_DjiReturnCode DjiAircraftInfo_GetConnectionStatus(bool *isConnected);
|
||||
*/
|
||||
T_DjiReturnCode DjiAircraftInfo_GetAircraftVersion(T_DjiAircraftVersion *aircraftVersion);
|
||||
|
||||
/**
|
||||
* @brief Get Enhanced Transmission state, which is set in the mobile app image transmission setting -- Enhanced Transmission.
|
||||
* @param aircraftVersion: Enhanced Transmission state.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiAircraftInfo_GetEnhancedTransmission(E_DjiEnhancedTransmissionState *state);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -682,6 +682,7 @@ typedef struct {
|
||||
E_DjiCameraManagerStreamSource streamSource[16];
|
||||
E_DjiCameraManagerStreamStorage streamStorage[16];
|
||||
E_DjiCameraManagerNightSceneMode nightSceneMode[16];
|
||||
E_DjiCameraManagerMeteringMode meteringMode[16];
|
||||
};
|
||||
uint32_t minValue;
|
||||
uint32_t maxValue;
|
||||
@ -850,7 +851,7 @@ T_DjiReturnCode DjiCameraManager_SetPhotoBurstCount(E_DjiMountPosition position,
|
||||
/**
|
||||
* @brief Set the parameters for INTERVAL shooting mode.
|
||||
* @note In this mode, the camera captures a photo, waits a specified interval
|
||||
* of time, then captures another photo, continuing until the set number of
|
||||
* of time, then captures another photo, continuing until the set number of
|
||||
* photos is reached. Supported by thermal imaging cameras, too.
|
||||
* @param position: camera mounted position
|
||||
* @param intervalSetting: refer to T_DjiCameraPhotoTimeIntervalSettings.
|
||||
@ -991,7 +992,7 @@ T_DjiReturnCode DjiCameraManager_GetTapZoomEnabled(E_DjiMountPosition position,
|
||||
|
||||
/**
|
||||
* @brief Set camera's tap-zoom multiplier of the selected camera mounted position.
|
||||
* @note The final zoom scale during a tap-zoom action will be:
|
||||
* @note The final zoom scale during a tap-zoom action will be:
|
||||
* Current Zoom Scale x Multiplier.
|
||||
* @param position: camera mounted position
|
||||
* @param tapZoomMultiplier: The multiplier range is [1,5]. A multiplier of 1 will not change the zoom.
|
||||
@ -1603,6 +1604,15 @@ T_DjiReturnCode DjiCameraManager_SetInfraredCameraGainMode(E_DjiMountPosition po
|
||||
T_DjiReturnCode DjiCameraManager_GetInfraredCameraGainModeTemperatureRange(E_DjiMountPosition position,
|
||||
T_DjiCameraManagerIrTempMeterRange *tempRange);
|
||||
|
||||
/**
|
||||
* @brief Get metergin mode range of infrared camera.
|
||||
* @param position: camera mounted position.
|
||||
* @param tempRange: returned value of metering range.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiCameraManager_GetMeteringModeRange(E_DjiMountPosition position,
|
||||
T_DjiCameraManagerRangeList *rangeList);
|
||||
|
||||
/**
|
||||
* @brief Set camera metering mode.
|
||||
* @param position: camera mounted position
|
||||
@ -1640,6 +1650,16 @@ T_DjiReturnCode DjiCameraManager_GetMeteringPointRegionRange(E_DjiMountPosition
|
||||
T_DjiReturnCode DjiCameraManager_SetMeteringPoint(E_DjiMountPosition position,
|
||||
uint8_t x, uint8_t y);
|
||||
|
||||
/**
|
||||
* @brief Set metering point normalize.
|
||||
* @param position: camera mounted position
|
||||
* @param x: Normalized horizontal coordinate, value ranges in 0 ~ 1.
|
||||
* @param y: Normalized Vertical coordinate, value ranges in 0 ~ 1.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiCameraManager_SetMeteringPointNormalized(E_DjiMountPosition position,
|
||||
dji_f32_t x, dji_f32_t y);
|
||||
|
||||
/**
|
||||
* @brief Get camera metering mode.
|
||||
* @param position: camera mounted position
|
||||
@ -1651,6 +1671,18 @@ T_DjiReturnCode DjiCameraManager_GetMeteringPoint(E_DjiMountPosition position,
|
||||
uint8_t *x, uint8_t *y);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get camera metering mode.
|
||||
* @param position: camera mounted position
|
||||
* @param x: a pointer to a float (dji_f32_t) that will receive the normalized x-coordinate of the
|
||||
* metering point.
|
||||
* @param y: a pointer to a float (dji_f32_t) that will receive the normalized y-coordinate of the
|
||||
* metering point.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiCameraManager_GetMeteringPointNormalized(E_DjiMountPosition position,
|
||||
dji_f32_t *x, dji_f32_t *y);
|
||||
|
||||
/**
|
||||
* @brief Start to record point cloud of the selected camera mounted position.
|
||||
* @param position: camera mounted position
|
||||
|
||||
@ -0,0 +1,60 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_cloud_api_by_websockt.h
|
||||
* @brief This is the header file for "dji_cloud_api_by_websockt.h", 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 DJI’s 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_CLOUD_API_BY_WEEBSOCKET_H
|
||||
#define DJI_CLOUD_API_BY_WEEBSOCKET_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_typedef.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
|
||||
/**
|
||||
* @brief Send data into cloud api channel over pilot2 websocket.
|
||||
* @note This interface should be called only on manifold3 application. It is recommended
|
||||
* to send more bytes of data at a time to improve read and write efficiency. Need to determine whether the send is
|
||||
* successful according to the return code and the actual sent data length.
|
||||
* @param data: pointer to data to be sent.
|
||||
* @param len: length of data to be sented to pilot2, unit: byte.
|
||||
* @param realLen: pointer to real length of data that already sent.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiCloudApi_SendDataByWebSocket(uint8_t *data, uint32_t len, uint32_t *realLen);
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
|
||||
@ -526,6 +526,153 @@ typedef enum {
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_IMU_ATTI_NAVI_DATA_WITH_TIMESTAMP = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 48),
|
||||
|
||||
/*!
|
||||
* @brief Provides postion NO.1 gimbal pitch, roll, yaw @ up to 50Hz
|
||||
* @details
|
||||
* The reference frame for gimbal angles is a NED frame attached to the gimbal.
|
||||
* This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is :
|
||||
* |Data Structure Element| Meaning|
|
||||
* |----------------------|--------|
|
||||
* |Vector3f.x |pitch |
|
||||
* |Vector3f.y |roll |
|
||||
* |Vector3f.z |yaw |
|
||||
*
|
||||
* @perf
|
||||
* 0.1 deg accuracy in all axes
|
||||
*
|
||||
* @sensors Gimbal Encoder, IMU, Magnetometer
|
||||
* @units deg
|
||||
* @datastruct \ref T_DjiFcSubscriptionGimbalAngles
|
||||
* @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO1 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 48),
|
||||
|
||||
/*!
|
||||
* @brief Provides postion NO.2 gimbal pitch, roll, yaw @ up to 50Hz
|
||||
* @details
|
||||
* The reference frame for gimbal angles is a NED frame attached to the gimbal.
|
||||
* This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is :
|
||||
* |Data Structure Element| Meaning|
|
||||
* |----------------------|--------|
|
||||
* |Vector3f.x |pitch |
|
||||
* |Vector3f.y |roll |
|
||||
* |Vector3f.z |yaw |
|
||||
*
|
||||
* @perf
|
||||
* 0.1 deg accuracy in all axes
|
||||
*
|
||||
* @sensors Gimbal Encoder, IMU, Magnetometer
|
||||
* @units deg
|
||||
* @datastruct \ref T_DjiFcSubscriptionGimbalAngles
|
||||
* @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO2 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 49),
|
||||
|
||||
/*!
|
||||
* @brief Provides postion NO.3 gimbal pitch, roll, yaw @ up to 50Hz
|
||||
* @details
|
||||
* The reference frame for gimbal angles is a NED frame attached to the gimbal.
|
||||
* This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is :
|
||||
* |Data Structure Element| Meaning|
|
||||
* |----------------------|--------|
|
||||
* |Vector3f.x |pitch |
|
||||
* |Vector3f.y |roll |
|
||||
* |Vector3f.z |yaw |
|
||||
*
|
||||
* @perf
|
||||
* 0.1 deg accuracy in all axes
|
||||
*
|
||||
* @sensors Gimbal Encoder, IMU, Magnetometer
|
||||
* @units deg
|
||||
* @datastruct \ref T_DjiFcSubscriptionGimbalAngles
|
||||
* @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO3 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 50),
|
||||
|
||||
/*!
|
||||
* @brief Provides postion NO.4 gimbal pitch, roll, yaw @ up to 50Hz
|
||||
* @details
|
||||
* The reference frame for gimbal angles is a NED frame attached to the gimbal.
|
||||
* This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is :
|
||||
* |Data Structure Element| Meaning|
|
||||
* |----------------------|--------|
|
||||
* |Vector3f.x |pitch |
|
||||
* |Vector3f.y |roll |
|
||||
* |Vector3f.z |yaw |
|
||||
*
|
||||
* @perf
|
||||
* 0.1 deg accuracy in all axes
|
||||
*
|
||||
* @sensors Gimbal Encoder, IMU, Magnetometer
|
||||
* @units deg
|
||||
* @datastruct \ref T_DjiFcSubscriptionGimbalAngles
|
||||
* @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO4 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 51),
|
||||
|
||||
/*!
|
||||
* @brief Provides postion NO.5 gimbal pitch, roll, yaw @ up to 50Hz
|
||||
* @details
|
||||
* The reference frame for gimbal angles is a NED frame attached to the gimbal.
|
||||
* This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is :
|
||||
* |Data Structure Element| Meaning|
|
||||
* |----------------------|--------|
|
||||
* |Vector3f.x |pitch |
|
||||
* |Vector3f.y |roll |
|
||||
* |Vector3f.z |yaw |
|
||||
*
|
||||
* @perf
|
||||
* 0.1 deg accuracy in all axes
|
||||
*
|
||||
* @sensors Gimbal Encoder, IMU, Magnetometer
|
||||
* @units deg
|
||||
* @datastruct \ref T_DjiFcSubscriptionGimbalAngles
|
||||
* @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO5 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 52),
|
||||
|
||||
/*!
|
||||
* @brief Provides postion NO.6 gimbal pitch, roll, yaw @ up to 50Hz
|
||||
* @details
|
||||
* The reference frame for gimbal angles is a NED frame attached to the gimbal.
|
||||
* This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is :
|
||||
* |Data Structure Element| Meaning|
|
||||
* |----------------------|--------|
|
||||
* |Vector3f.x |pitch |
|
||||
* |Vector3f.y |roll |
|
||||
* |Vector3f.z |yaw |
|
||||
*
|
||||
* @perf
|
||||
* 0.1 deg accuracy in all axes
|
||||
*
|
||||
* @sensors Gimbal Encoder, IMU, Magnetometer
|
||||
* @units deg
|
||||
* @datastruct \ref T_DjiFcSubscriptionGimbalAngles
|
||||
* @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO6 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 53),
|
||||
|
||||
/*!
|
||||
* @brief Provides postion NO.7 gimbal pitch, roll, yaw @ up to 50Hz
|
||||
* @details
|
||||
* The reference frame for gimbal angles is a NED frame attached to the gimbal.
|
||||
* This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is :
|
||||
* |Data Structure Element| Meaning|
|
||||
* |----------------------|--------|
|
||||
* |Vector3f.x |pitch |
|
||||
* |Vector3f.y |roll |
|
||||
* |Vector3f.z |yaw |
|
||||
*
|
||||
* @perf
|
||||
* 0.1 deg accuracy in all axes
|
||||
*
|
||||
* @sensors Gimbal Encoder, IMU, Magnetometer
|
||||
* @units deg
|
||||
* @datastruct \ref T_DjiFcSubscriptionGimbalAngles
|
||||
* @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO7 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 54),
|
||||
|
||||
/*! Total number of topics that can be subscribed. */
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_TOTAL_NUMBER,
|
||||
} E_DjiFcSubscriptionTopic;
|
||||
|
||||
@ -29,7 +29,6 @@
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_typedef.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
@ -114,6 +113,7 @@ typedef enum {
|
||||
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.*/
|
||||
DJI_FLIGHT_CONTROLLER_DOCK_REQUEST_CHANGE_JOYSTICK_CTRL_AUTH_EVENT = 13, /*!< Dock request change the joystick control permission.*/
|
||||
} E_DjiFlightControllerJoystickCtrlAuthoritySwitchEvent;
|
||||
|
||||
/**
|
||||
@ -237,6 +237,17 @@ typedef enum {
|
||||
DJI_FLIGHT_CONTROLLER_DISABLE_RC_LOST_ACTION = 1,
|
||||
} E_DjiFlightControllerRCLostActionEnableStatus;
|
||||
|
||||
typedef enum {
|
||||
DJI_FLIGHT_CONTROLLER_NO_MOTOR_IN_SLOW_ROTATE_MODE = 0,
|
||||
DJI_FLIGHT_CONTROLLER_SOME_MOTOR_IN_SLOW_ROTATE_MODE = 1,
|
||||
DJI_FLIGHT_CONTROLLER_ALL_MOTOR_IN_SLOW_ROTATE_MODE = 2,
|
||||
} E_DjiFlightControllerElectronicSpeedControllerStatus;
|
||||
|
||||
typedef enum {
|
||||
DJI_FLIGHT_CONTROLLER_FTS_NOT_TRIGGERD = 0,
|
||||
DJI_FLIGHT_CONTROLLER_FTS_TRIGGERD = 1,
|
||||
} E_DjiFlightControllerFtsStatus;
|
||||
|
||||
/**
|
||||
* @brief Joystick mode.
|
||||
* @note You need to set joystick mode first before start to send joystick command to aircraft.
|
||||
@ -272,6 +283,62 @@ typedef struct {
|
||||
uint16_t altitude;
|
||||
} T_DjiFlightControllerRidInfo;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
double lat; /*!< Target point latitude, unit: rad */
|
||||
double lon; /*!< Target point longitude, unit: rad */
|
||||
float alt; /*!< Target point altitude, ellipsoidal height unit: meters */
|
||||
} T_DjiFlightControllerPointInfo;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t version; /*!< Function version */
|
||||
int8_t operation; /*!< New upload of a target point or update of the current task's target point; 0: new order, 1: update goal */
|
||||
float mea; /*!< Minimum enroute height, in meters, relative to the takeoff point.
|
||||
If the aircraft has not started or is on the ground, it will first climb to this height before executing the task. This height is ignored if the aircraft is in the air. */
|
||||
uint8_t fly_vel; /*!< Maximum horizontal flight speed to the target point, in meters per second */
|
||||
uint8_t goal_num; /*!< Number of target points, currently only supports one point */
|
||||
T_DjiFlightControllerPointInfo cmd_mode_point_info[1]; /*!< Information of the target point */
|
||||
} T_DjiFlightControllerStartMissionReq;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t ret_code; /*!< 0: Start task successfully, 1: Start task failed */
|
||||
uint16_t error_code; /*!< Instruction flight route version reused route error code */
|
||||
uint8_t code_name; /*!< Task code, unique, will be included in the trajectory push to ensure that external modules can correlate the task with its trajectory */
|
||||
} T_DjiFlightControllerStartMissionRsp;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t mission_state_machine; /*!< Task state machine, 0 is idle, others are in progress.*/
|
||||
uint8_t mission_planning_algo; /*!< Task planning algorithm mode */
|
||||
uint8_t goal_index; /*!< Current target point index */
|
||||
float distance_remaining; /*!< Remaining task distance */
|
||||
float time_remaining; /*!< Remaining task time */
|
||||
uint8_t soe_remaining; /*!< Required SOE (State of Energy) */
|
||||
uint8_t progress; /*!< Progress, reserved unused */
|
||||
uint8_t success_rate; /*!< Task success rate, reserved unused */
|
||||
} T_DjiFlightControllerOpenMis;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
int32_t latitude; /*!< GPS latitude, unit: 1/2^32 * 180°, range: [-90°, 90°) */
|
||||
int32_t longitude; /*!< GPS longitude, unit: 1/2^32 * 360°, range: [-180°, 180°) */
|
||||
int32_t altitude; /*!< Altitude, unit: mm; Note: The type of altitude depends on the function definition.
|
||||
It could be: relative to the takeoff point, WGS84 absolute ellipsoidal height, EGM96 absolute altitude, barometric height, etc. */
|
||||
} T_DjiFlightControllerSpotlightZoomGps;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t code_name; /*!< Unique task code for this trajectory push */
|
||||
uint8_t point_num; /*!< Number of key points in the trajectory */
|
||||
uint8_t byte_per_point; /*!< Number of bytes per point */
|
||||
T_DjiFlightControllerSpotlightZoomGps points[1]; /*!< Array of key points in the trajectory */
|
||||
uint8_t last_point_type; /*!< Whether the target point can be reached
|
||||
0: Yes, the last point in the trajectory is the user's target point
|
||||
1: No, the user's target point is in an invalid area (e.g., within an NFZ or building), the last point is the closest point to the target */
|
||||
} T_DjiFlightControllerCoreTraj;
|
||||
|
||||
#pragma pack()
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
@ -288,6 +355,81 @@ T_DjiReturnCode DjiFlightController_Init(T_DjiFlightControllerRidInfo ridInfo);
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_DeInit(void);
|
||||
|
||||
/**
|
||||
* @brief Set planning algorithm.
|
||||
* @param algo: 0:smart height, 1:Manual height.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_SetPlanningAlgo(uint8_t algo);
|
||||
|
||||
/**
|
||||
* @brief Set max velocity.
|
||||
* @param value: max velocity value, min:1, max:15.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_SetMaxVelocity(uint8_t value);
|
||||
|
||||
/**
|
||||
* @brief Set min flight height.
|
||||
* @param value: min flight height value, min:1.0, max:3000.0, only SetPlanningAlgo 1 effective.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_SetMinFlightHeight(float value);
|
||||
|
||||
/**
|
||||
* @brief Get exit reason.
|
||||
* @param reason: exit reason".
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_GetExitReason(uint16_t *reason);
|
||||
|
||||
/**
|
||||
* @brief Prototype of callback function used to get open mis info.
|
||||
* @return Execution result.
|
||||
*/
|
||||
typedef T_DjiReturnCode (*FcCmderModeOpenMisEventCbFunc)(T_DjiFlightControllerOpenMis eventData);
|
||||
|
||||
/**
|
||||
* @brief Prototype of callback function used to get core traj info.
|
||||
* @return Execution result.
|
||||
*/
|
||||
typedef T_DjiReturnCode (*FcCmderModeCoreTrajEventCbFunc)(T_DjiFlightControllerCoreTraj eventData);
|
||||
|
||||
/**
|
||||
* @brief Register callback function for the open mis event.
|
||||
* @param callback: the callback for the open mis event.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_RegisterOpenMisInfoCallBack(FcCmderModeOpenMisEventCbFunc callback);
|
||||
|
||||
/**
|
||||
* @brief Register callback function for the core traj event.
|
||||
* @param callback: the callback for the core traj event.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_RegisterCoreTrajCallBack(FcCmderModeCoreTrajEventCbFunc callback);
|
||||
|
||||
/**
|
||||
* @brief antiregister callback function for the open mis event.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_AntiRegisterOpenMisInfoCallBack(void);
|
||||
|
||||
/**
|
||||
* @brief antiregister callback function for the core traj event.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_AntiRegisterCoreTrajCallBack(void);
|
||||
|
||||
/**
|
||||
* @brief set mode start mission.
|
||||
* @param command: cmd for start mission.
|
||||
* @param rsp: response data for set start mission.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_SetModeStartMission(T_DjiFlightControllerStartMissionReq command,
|
||||
T_DjiFlightControllerStartMissionRsp *rsp);
|
||||
|
||||
/**
|
||||
* @brief Enable/Disable RTK position function.
|
||||
* @details Enabling RTK means that RTK data will be used instead of GPS during flight.
|
||||
@ -649,6 +791,25 @@ DjiFlightController_GetEnableRCLostActionStatus(E_DjiFlightControllerRCLostActio
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_RegTriggerFtsEventCallback(TriggerFtsEventCallback callback);
|
||||
|
||||
/**
|
||||
* @brief Start to rotate motors slowly.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_StartSlowRotateMotor(void);
|
||||
|
||||
/**
|
||||
* @brief Stop to rotate motors slowly.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_StopSlowRotateMotor(void);
|
||||
|
||||
/**
|
||||
* @brief Get the status of the ESC.
|
||||
* @param status: The status of the motor on aircraft.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_GetElectronicSpeedControllerStatus(E_DjiFlightControllerElectronicSpeedControllerStatus *status);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
86
Source/M300/PSDK_Qt/psdk_lib/include/dji_fts.h
Normal file
86
Source/M300/PSDK_Qt/psdk_lib/include/dji_fts.h
Normal file
@ -0,0 +1,86 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_network_rtk.h
|
||||
* @version V1.0.0
|
||||
* @date 2025/10/09
|
||||
* @brief This is the header file for "dij_core.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 DJI’s 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_NETWORK_RTK_H
|
||||
#define DJI_NETWORK_RTK_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_typedef.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
typedef enum {
|
||||
DJI_FTS_NOT_TRIGGERD = 0,
|
||||
DJI_FTS_TRIGGERD = 1,
|
||||
} E_DjiFtsStatus;
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
typedef struct {
|
||||
E_DjiMountPosition fts_select;
|
||||
E_DjiFtsStatus fts_status;
|
||||
uint8_t fts_pwm_cnt; /* correct number of PWM signals received */
|
||||
} T_DjiFtsPwmTriggerStatus;
|
||||
|
||||
typedef struct {
|
||||
T_DjiFtsPwmTriggerStatus ESC[4]; /* trigger status of the two ESCs */
|
||||
} T_DjiFtsPwmEscTriggerStatus;
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Select Fts pwm trigger.
|
||||
* - Notes:Timing requirement: This API must be called while the aircraft is on the ground (not airborne). Calls made during flight will fail or be rejected.
|
||||
* - Function: This call only selects/enables the PWM trigger port on the flight controller side.
|
||||
* It does NOT emit PWM signals nor perform the motor-stop action itself. The actual motor-stop must be triggered by sending PWM signals via external PWM hardware pins.
|
||||
* - Recommended flow:
|
||||
* 1) Call DjiFlightController_SelectFtsPwmTrigger(position) on ground to enable the port;
|
||||
* 2) Send the motor-stop PWM from an external PWM controller to that port;
|
||||
* @param position
|
||||
* - Supported models/ports:
|
||||
* - M400: only support DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO4.
|
||||
* @return Possible failure reasons include invalid param, aircraft not on ground, hardware unsupported, or module not initialized.
|
||||
*/
|
||||
T_DjiReturnCode DjiFts_SelectFtsPwmTrigger(E_DjiMountPosition position);
|
||||
|
||||
/**
|
||||
* @brief Get Fts pwm trigger status.
|
||||
* Notes:This API is deprecated and will be removed in a future release. It is NOT recommended for use. Supported models only: M4 serials.
|
||||
* Recommended alternative: To confirm motor-stop (FTS) effects, use DJI_FC_SUBSCRIPTION_TOPIC_ESC_DATA fc subscription
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFts_GetFtsPwmTriggerStatus(T_DjiFtsPwmEscTriggerStatus* trigger_status);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // DIJ_CORE_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
@ -44,6 +44,18 @@ typedef enum {
|
||||
DJI_HMS_ERROR_LEVEL_FATAL,
|
||||
} E_DjiHmsErrorLevel;
|
||||
|
||||
typedef enum {
|
||||
DJI_HMS_ALARM_ENHANCED_TYPE_SHAKE_MOTOR = 1, /*!< Alarm triggered by shaking the motor on the pilot; alerts the user with vibrations indicating a warning or fault. */
|
||||
DJI_HMS_ALARM_ENHANCED_PLAY_SOUND = 2, /*!< Alarm triggered by playing sound */
|
||||
DJI_HMS_ALARM_ENHANCED_PLAY_SOUND_AND_SHAKE_MOTOR =3, /*!< Alarm that alerts the user on the PILOT app with both sound and vibrations */
|
||||
} E_DjiHmsAlarmEnhancedType;
|
||||
|
||||
typedef enum {
|
||||
DJI_HMS_ALARM_ENHANCED_ACTION_STOP = 0, /*!< Action to stop a specific enhanced alarm, shake motor or play sound */
|
||||
DJI_HMS_ALARM_ENHANCED_ACTION_START = 1, /*!< Action to stop a specific enhanced alarm */
|
||||
DJI_HMS_ALARM_ENHANCED_ACTION_EXIT_ALL =2,/*!< Action to exit all enhanced alarms, both shake motor and play sound; */
|
||||
} E_DjiHmsAlarmEnhancedAction;
|
||||
|
||||
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 */
|
||||
@ -55,6 +67,11 @@ typedef struct {
|
||||
T_DjiHmsFileBinaryArray *fileBinaryArrayList; /*!< Pointer to binary array list */
|
||||
} T_DjiHmsBinaryArrayConfig;
|
||||
|
||||
typedef struct {
|
||||
E_DjiHmsAlarmEnhancedType type; /*!< The type is used to specify which enhanced alarm to ACTION_STOP or ACTION_START. It is ignored when EXIT_ALL alarms.*/
|
||||
int8_t times; /* !< Specifies the number of consecutive times the alarm is to be activated.*/
|
||||
int16_t interval; /* !< Indicates the interval (in milliseconds) between consecutive activations of the alarm.*/
|
||||
} T_DjiHmsAlarmEnhancedSetting;
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
/**
|
||||
@ -65,7 +82,7 @@ typedef struct {
|
||||
T_DjiReturnCode DjiHmsCustomization_Init(void);
|
||||
|
||||
/**
|
||||
* @brief DeInitialize hms manager module.
|
||||
* @brief DeInitialize hms customization module.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiHmsCustomization_DeInit(void);
|
||||
@ -125,6 +142,15 @@ T_DjiReturnCode DjiHmsCustomization_RegDefaultHmsTextConfigByBinaryArray(const T
|
||||
T_DjiReturnCode DjiHmsCustomization_RegHmsTextConfigByBinaryArray(E_DjiMobileAppLanguage appLanguage,
|
||||
const T_DjiHmsBinaryArrayConfig *binaryArrayConfig);
|
||||
|
||||
/**
|
||||
* @brief Contrl the app alram.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @param action: The action to start or stop alarm.
|
||||
* @param setting: The alarm information.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiHmsCustomization_AlarmEnhancedCtrl(E_DjiHmsAlarmEnhancedAction action, T_DjiHmsAlarmEnhancedSetting setting);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -39,16 +39,23 @@ extern "C" {
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
typedef enum {
|
||||
DJI_INTEREST_POINT_MISSION_ACTION_STATE_NOT_STARTED = 0,
|
||||
DJI_INTEREST_POINT_MISSION_ACTION_STATE_PAUSE = 1,
|
||||
DJI_INTEREST_POINT_MISSION_ACTION_STATE_RUNNING = 2,
|
||||
} E_DjiInterestPointActionState;
|
||||
|
||||
typedef struct {
|
||||
dji_f32_t curSpeed;
|
||||
dji_f32_t radius;
|
||||
uint8_t state;
|
||||
uint8_t state; /*!< Refer to E_DjiInterestPointActionState.*/
|
||||
} T_DjiInterestPointMissionState;
|
||||
|
||||
typedef struct {
|
||||
dji_f64_t latitude;
|
||||
dji_f64_t longitude;
|
||||
dji_f32_t speed;
|
||||
int8_t payloadCameraIndex; /*!< Used by which aircraft that can mount payload cameras. Range starts from 1.*/
|
||||
} T_DjiInterestPointSettings;
|
||||
|
||||
typedef T_DjiReturnCode (*InterestPointMissionStateCallback)(T_DjiInterestPointMissionState missionState);
|
||||
|
||||
@ -47,6 +47,15 @@ typedef enum {
|
||||
DJI_LIVEVIEW_CAMERA_POSITION_FPV = 7
|
||||
} E_DjiLiveViewCameraPosition;
|
||||
|
||||
/**
|
||||
* @brief Image format.
|
||||
*/
|
||||
typedef enum {
|
||||
PIXFMT_NV12 = 3,
|
||||
PIXFMT_RGB_PLANAR = 4,
|
||||
PIXFMT_RGB_PACKED = 5
|
||||
} E_DjiLiveViewPixFormate;
|
||||
|
||||
/**
|
||||
* @brief Liveview camera stream source.
|
||||
*/
|
||||
@ -71,13 +80,105 @@ typedef enum {
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M3D_VIS = 1,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M3TD_VIS = 1,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M3TD_IR = 2,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_H30_ZOOM = 1,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_H30_4K = 7,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M4E_VIS = 1,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M4E_4K = 3,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M4T_VIS = 1,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M4T_IR = 2,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M4T_4K = 3,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M4D_VIS = 1,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M4D_4K = 3,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M4TD_VIS = 1,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M4TD_IR = 2,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M4TD_4K = 3,
|
||||
} E_DjiLiveViewCameraSource;
|
||||
|
||||
/**
|
||||
* @brief DJI standard types of target recognition.
|
||||
*/
|
||||
typedef enum {
|
||||
DJI_LIVEVIEW_OBJ_TYPE_INVALID = 0,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_UNKNOWN = 1,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_PERSON = 2,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_CAR = 3,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_BOAT = 4,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_HUMAN_FACE = 5,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_BIRD = 10,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_BEACON = 20,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_GPS = 30,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_MOVING_TARGET = 34,
|
||||
} E_DjiLiveViewTargetObjectType;
|
||||
|
||||
/**
|
||||
* @brief Target Recognition Status.
|
||||
*/
|
||||
typedef enum {
|
||||
DJI_LIVEVIEW_OBJ_STATE_INVALID = 0, /*!< invalid state */
|
||||
DJI_LIVEVIEW_OBJ_STATE_TRACKED = 1, /*!< steady state following */
|
||||
DJI_LIVEVIEW_OBJ_STATE_VISION_BEACON_FUSIONED = 2, /*!< Vision beacon fusion state */
|
||||
DJI_LIVEVIEW_OBJ_STATE_AUXILIARY_TRACKED = 3, /*!< Loss of trigger source, auxiliary observation following state */
|
||||
DJI_LIVEVIEW_OBJ_STATE_NOT_CONFIDENT = 4, /*!< unstable following state */
|
||||
DJI_LIVEVIEW_OBJ_STATE_LOST_WITH_PREDICT = 5, /*!< Target lost, forecast status maintained */
|
||||
DJI_LIVEVIEW_OBJ_STATE_LOST = 6, /*!< Target Loss Status */
|
||||
DJI_LIVEVIEW_OBJ_STATE_REDETECTED = 7, /*!< Target Loss Retrieval Status */
|
||||
} E_DjiLiveViewTargetObjectState;
|
||||
|
||||
/**
|
||||
* @brief Picture frame information for target recognition results
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint16_t cx; /*!< X-coordinate of the center of the frame, unit: 1/10000 * screen width */
|
||||
uint16_t cy; /*!< Y-coordinate of the center of the frame, unit: 1/10000 * screen height */
|
||||
uint16_t w; /*!< Frame width, unit: 1/10000 * screen width */
|
||||
uint16_t h; /*!< Frame height, unit: 1/10000 * screen height */
|
||||
uint32_t distance; /*!< Distance in mm */
|
||||
} __attribute__((packed)) T_DjiLiveViewTarget2dBox;
|
||||
|
||||
/**
|
||||
* @brief BoundingBox information for target recognition.
|
||||
*/
|
||||
typedef struct {
|
||||
uint16_t id;
|
||||
uint8_t type; /*!< type can be an enumerated value of E_DjiLiveViewTargetObjectType or a user-defined value. */
|
||||
uint8_t state; /*!< state should be of type E_DjiLiveViewTargetObjectState enumeration */
|
||||
T_DjiLiveViewTarget2dBox box;
|
||||
} __attribute__((packed)) T_DjiLiveViewBoundingBox;
|
||||
|
||||
/**
|
||||
* @brief List of boundingBox information.
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t boxCount;
|
||||
T_DjiLiveViewBoundingBox boxData[1];
|
||||
} __attribute__((packed)) T_DjiLiveViewStandardMetaData;
|
||||
|
||||
/**
|
||||
* @brief Image information.
|
||||
*/
|
||||
typedef struct {
|
||||
E_DjiLiveViewPixFormate pixFmt;
|
||||
uint16_t width;
|
||||
uint16_t height;
|
||||
uint32_t frameId;
|
||||
} T_DjiLiveviewImageInfo;
|
||||
|
||||
/**
|
||||
* @brief Liveview camera h264 stream callback.
|
||||
*/
|
||||
typedef void (*DjiLiveview_H264Callback)(E_DjiLiveViewCameraPosition position, const uint8_t *buf, uint32_t len);
|
||||
|
||||
/**
|
||||
* @brief Liveview camera image data callback.
|
||||
*/
|
||||
typedef void (*DjiLiveview_ImageCallback)(E_DjiLiveViewCameraPosition position, const uint8_t *buf,
|
||||
uint32_t len , T_DjiLiveviewImageInfo ImageInfo);
|
||||
|
||||
/**
|
||||
* @brief Callback for handling encoded output data
|
||||
*/
|
||||
typedef void (*DjiLiveview_EncoderCallback)(const uint8_t *buf, uint32_t len);
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Initialize the liveview module.
|
||||
@ -119,6 +220,81 @@ T_DjiReturnCode DjiLiveview_StopH264Stream(E_DjiLiveViewCameraPosition position,
|
||||
T_DjiReturnCode DjiLiveview_RequestIntraframeFrameData(E_DjiLiveViewCameraPosition position,
|
||||
E_DjiLiveViewCameraSource source);
|
||||
|
||||
/**
|
||||
* @brief Request to get the decoded image data from the specified position.
|
||||
* @param position: Camera position for the H264 stream.
|
||||
* @param source: sub-camera source for the H264 stream.
|
||||
* @param pixFmt: Requested Image Format.
|
||||
* @param callback: Callback for handling image data.
|
||||
* @return Execution result.
|
||||
* @note This interface support on DJI manifold3.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_StartImageStream(E_DjiLiveViewCameraPosition position, E_DjiLiveViewCameraSource source,
|
||||
E_DjiLiveViewPixFormate pixFmt, DjiLiveview_ImageCallback callback);
|
||||
|
||||
/**
|
||||
* @brief Stop the decoded image data from the specified position.
|
||||
* @param position: Camera position for the H264 stream.
|
||||
* @param source: sub-camera source for the H264 stream.
|
||||
* @return Execution result.
|
||||
* @note This interface support on DJI manifold3.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_StopImageStream(E_DjiLiveViewCameraPosition position, E_DjiLiveViewCameraSource source);
|
||||
|
||||
/**
|
||||
* @brief Registering encoder callback handlers.
|
||||
* @return Execution result.
|
||||
* @note This interface support on DJI manifold3.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_RegEncoderCallback(DjiLiveview_EncoderCallback callback);
|
||||
|
||||
/**
|
||||
* @brief Unregistering encoder callback handlers.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_UnregEncoderCallback();
|
||||
|
||||
/**
|
||||
* @brief Encoding image into h264 streams.
|
||||
* @param buf: raw data of image.
|
||||
* @param len: length of image data.
|
||||
* @param imageInfo: information of image.
|
||||
* @param metaData: Resulting information obtained from images for target recognition.
|
||||
* @return Execution result.
|
||||
* @note If there is no need for information related to target identification, fill in NULL for metaData.
|
||||
* @note This interface needs to be used after DjiLiveview_RegEncoderCallback.
|
||||
* @note This interface support on DJI manifold3.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_EncodeAFrameToH264(const uint8_t *buf, uint32_t len, T_DjiLiveviewImageInfo imageInfo,
|
||||
T_DjiLiveViewStandardMetaData *metaData);
|
||||
|
||||
/**
|
||||
* @brief Register user-defined target Lables
|
||||
* @param lableCount: Number of lable.
|
||||
* @param labels: lable String Array
|
||||
* @note The key-value pairs of lable and index will be recorded on the Pilot after registration
|
||||
* and will be used to parse the metaData and display the lable when rendering the boundingbox.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_RegUserAiTargetLableList(uint8_t lableCount,const char *labels[]);
|
||||
|
||||
/**
|
||||
* @brief Unregister user-defined target Lables
|
||||
* @return Execution result.
|
||||
* @note This interface support on DJI manifold3.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_UnregUserAiTargetLableList();
|
||||
|
||||
/**
|
||||
* @brief Transmits the result information of the target recognition to the pilot for display.
|
||||
* @param metaData: Resulting information obtained from images for target recognition.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_SendAiMetaToPilot(T_DjiLiveViewStandardMetaData *metaData);
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -102,14 +102,24 @@ T_DjiReturnCode DjiLogger_RemoveConsole(T_DjiLoggerConsole *console);
|
||||
void DjiLogger_UserLogOutput(E_DjiLoggerConsoleLogLevel level, const char *fmt, ...);
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
#define __FILENAME__ (strrchr("/" __FILE__, '/') + 1)
|
||||
|
||||
#define USER_LOG_PREFIX_FMT "%25s:%-4d "
|
||||
|
||||
#ifndef SYSTEM_ARCH_RTOS
|
||||
#define USER_LOG_PREFIX_ARG __FILENAME__, __LINE__
|
||||
#else
|
||||
#define USER_LOG_PREFIX_ARG __FUNCTION__, __LINE__
|
||||
#endif
|
||||
|
||||
#define USER_LOG_DEBUG(fmt, ...) \
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_DEBUG, "[%s:%d) " fmt, __FUNCTION__, __LINE__ , ##__VA_ARGS__)
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_DEBUG, USER_LOG_PREFIX_FMT fmt, USER_LOG_PREFIX_ARG, ##__VA_ARGS__)
|
||||
#define USER_LOG_INFO(fmt, ...) \
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO, "[%s:%d) " fmt, __FUNCTION__, __LINE__ , ##__VA_ARGS__)
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO, USER_LOG_PREFIX_FMT fmt, USER_LOG_PREFIX_ARG, ##__VA_ARGS__)
|
||||
#define USER_LOG_WARN(fmt, ...) \
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_WARN, "[%s:%d) " fmt, __FUNCTION__, __LINE__ , ##__VA_ARGS__)
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_WARN, USER_LOG_PREFIX_FMT fmt, USER_LOG_PREFIX_ARG, ##__VA_ARGS__)
|
||||
#define USER_LOG_ERROR(fmt, ...) \
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_ERROR, "[%s:%d) " fmt, __FUNCTION__, __LINE__ , ##__VA_ARGS__)
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_ERROR, USER_LOG_PREFIX_FMT fmt, USER_LOG_PREFIX_ARG, ##__VA_ARGS__)
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
||||
130
Source/M300/PSDK_Qt/psdk_lib/include/dji_network_rtk.h
Normal file
130
Source/M300/PSDK_Qt/psdk_lib/include/dji_network_rtk.h
Normal file
@ -0,0 +1,130 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_network_rtk.h
|
||||
* @version V1.0.0
|
||||
* @date 2025/10/09
|
||||
* @brief This is the header file for "dij_core.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 DJI’s 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_NETWORK_RTK_H
|
||||
#define DJI_NETWORK_RTK_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_typedef.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
/**
|
||||
* @brief The network rtk state.
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
DJI_LOG_IN = 0, /*! Logging in (login in progress) */
|
||||
DJI_CONNECTING = 1,/*! Connecting to remote/server */
|
||||
DJI_TRANSFER = 2, /*! Data transfer in progress */
|
||||
DJI_RECONNECT = 3, /*! Reconnecting (attempting to restore connection) */
|
||||
DJI_BROKEN = 4, /*! Connection broken / disconnected from remote server */
|
||||
DJI_STOPPING = 5, /*! Stopping (shutdown in progress) */
|
||||
DJI_REBOOTING = 6, /*! Rebooting: waiting for restart after switching source) */
|
||||
} E_DjiNetworkRtkOnboardState;
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Position of target point and other details returned by interface of requesting position.
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t account[16]; /*!< RTK account (username). Null-terminated string, up to 15 chars + '\0'. */
|
||||
uint8_t password[64]; /*!< RTK password. Null-terminated string, up to 63 chars + '\0'. */
|
||||
uint8_t host[64]; /*!< IP address of the NTRIP caster/host.MUST be a valid IPv4 or IPv6 address. Domain names (e.g., "example.com") are NOT supported.*/
|
||||
|
||||
/*!< NTRIP port information. Often used to indicate coordinate system info for some providers.
|
||||
* Field MUST be a string. The string SHOULD represent an integer value in
|
||||
* the range 1 to 65535 (inclusive). Example valid values: "80", "443", "2101".*/
|
||||
uint8_t port[6];
|
||||
|
||||
/*!< NTRIP mountpoint information. Typically configures RTCM system.
|
||||
* -Allowed characters: a-z, A-Z, 0-9, '-' (hyphen), '_' (underscore), '.' (dot).
|
||||
* -Disallowed characters include (but are not limited to): space, '@', '#', '$'.
|
||||
* -Recommended validation regex: /^[A-Za-z0-9._-]+$/ */
|
||||
uint8_t mountPoint[32];
|
||||
} T_DjiNetworkRtkServiceConfig;
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
|
||||
/**
|
||||
* @brief Register a callback function to receive network RTK service state updates.
|
||||
* @note This callback is used to asynchronously obtain the state of the network RTK service.
|
||||
* It is recommended to register the callback before starting the network RTK service.
|
||||
* @param callback [in] Pointer to the user-implemented callback function for handling received network RTK state data.
|
||||
* @return Execution result.
|
||||
*/
|
||||
typedef void (*DjiReceiveNetworkRtkStateCallback)(E_DjiNetworkRtkOnboardState state);
|
||||
T_DjiReturnCode DjiNetworkRtk_RegReceiveNetworkRtkStateCallback(DjiReceiveNetworkRtkStateCallback callback);
|
||||
/**
|
||||
* @brief Start the network RTK service.
|
||||
* @note
|
||||
* Behavior and usage notes:
|
||||
* - RTK service state updates are delivered via
|
||||
* DjiPositioning_RegReceiveNetworkRtkStateCallback. Monitor that callback
|
||||
* to observe state transitions (e.g., DJI_REBOOTING, DJI_TRANSFER).
|
||||
* - Note: If the current RTK source is NOT a custom network source, the first call
|
||||
* to this API will require a device reboot to switch to the network RTK
|
||||
* source. After the device reboots, you must call this API again to start
|
||||
* the Network RTK service so that it takes effect.
|
||||
* - DJI_REBOOTING indicates that a reboot is required/underway to apply the
|
||||
* change of RTK source. Note: the device will NOT reboot automatically;
|
||||
* a manual reboot is required to complete the change.
|
||||
* - DJI_TRANSFER indicates that the RTK service is connected and data
|
||||
* transfer between RTK endpoints has been established. DJI_TRANSFER does
|
||||
* NOT guarantee that the RTK solution has converged to a usable fix.
|
||||
* Convergence must be verified by subscribing to RTK positioning data and
|
||||
* checking the quality/accuracy indicators provided in those data messages.
|
||||
*
|
||||
* Recommended call sequence:
|
||||
* 1. Call DjiPositioning_StartNetworkRtkService().
|
||||
* 2. If state callback reports DJI_REBOOTING, perform a MANUAL reboot of the device.
|
||||
* 3. After the manual reboot, call DjiPositioning_StartNetworkRtkService() again.
|
||||
* 4. Monitor state callback for DJI_TRANSFER and subscribe to RTK position
|
||||
* data to verify convergence.
|
||||
* @param config [in] Pointer to a T_DjiNetworkRtkServiceConfig structure containing the configuration information for the network RTK service.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiNetworkRtk_StartService(const T_DjiNetworkRtkServiceConfig* config);
|
||||
|
||||
/**
|
||||
* @brief Stop the network RTK service.
|
||||
* @note After calling this function, the device will disconnect from the network RTK service and stop receiving high-precision positioning data.
|
||||
* @param None
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiNetworkRtk_StopService(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // DIJ_CORE_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
389
Source/M300/PSDK_Qt/psdk_lib/include/dji_open_ar.h
Normal file
389
Source/M300/PSDK_Qt/psdk_lib/include/dji_open_ar.h
Normal file
@ -0,0 +1,389 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_open_ar.h
|
||||
* @brief This is the header file for "dji_open_ar.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 DJI’s 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_OPEN_AR_H
|
||||
#define DJI_OPEN_AR_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_typedef.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
typedef struct
|
||||
{
|
||||
float longitude;
|
||||
float latitude;
|
||||
float altitude;
|
||||
} T_DjiOpenArCoordinate;
|
||||
|
||||
/**
|
||||
* @brief Text information definition
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t is_show:1; /*!< Whether to display, 0: not display, 1: display */
|
||||
uint8_t text[30]; /*!< Text information, with '\0' as the terminator */
|
||||
} T_DjiOpenArTextAttribute;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t selected:1; /*!< Whether selected, 0: not selected, 1: selected */
|
||||
uint8_t visible :1; /*!< Whether to display, 0: not display, 1: display */
|
||||
uint32_t color; /*!< Contains alpha channel */
|
||||
} T_DjiOpenArIconAttribute;
|
||||
|
||||
/**
|
||||
* @brief Click action for a point
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t action; /*!< 0: click; 1: drag along the line; 2: drag from a distance */
|
||||
T_DjiOpenArCoordinate normal_vector; /*!< Dragging direction: normal vector */
|
||||
} T_DjiOpenArTouchAttribute;
|
||||
|
||||
/**
|
||||
* @brief Represents the unique identifier for AR elements
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint32_t uuid; /*!< uuid used for updating and deleting */
|
||||
uint32_t style_id; /*!< used to index resources config, corresponding resource is configured in widget.json */
|
||||
} T_DjiOpenArIds;
|
||||
|
||||
/**
|
||||
* @brief AR face drawing attributes
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t dist_alpha_enable :1; /*!< Enable distance-based alpha blending (1) or not (0) */
|
||||
uint8_t face_bottom_enable:1; /*!< Enable drawing bottom face (1) or not (0) */
|
||||
uint8_t face_side_enable :1; /*!< Enable drawing side face (1) or not (0) */
|
||||
uint8_t face_top_enable :1; /*!< Enable drawing top face (1) or not (0) */
|
||||
} T_DjiOpenArPolygonFaceAttribute;
|
||||
|
||||
/**
|
||||
* @brief AR border drawing attributes
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t top_show :1;
|
||||
uint8_t top_dist_alpha_enable :1;
|
||||
uint8_t side_show :1;
|
||||
uint8_t side_dist_alpha_enable :1;
|
||||
uint8_t bottom_show :1;
|
||||
uint8_t bottom_dist_alpha_enable:1;
|
||||
} T_DjiOpenArPolygonStrokeAttribute;
|
||||
|
||||
/**
|
||||
* @brief AR pint drawing attibutes
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint32_t uuid; /*!< uuid for point , used to updating and delting */
|
||||
uint32_t style_id; /*!< dentifier for the style associated with the point, define with widget.json */
|
||||
uint32_t resource_id; /*!< Identifier for the resource associated with the point */
|
||||
uint8_t is_always_in_edge; /*!< Whether the point is always on the edge */
|
||||
T_DjiOpenArCoordinate coordinate; /*!< Physical position in the world coordinate system */
|
||||
T_DjiOpenArTextAttribute text_attr; /*!< Attributes related to the text associated with the point */
|
||||
T_DjiOpenArIconAttribute icon_attr; /*!< Attributes related to the icon associated with the point */
|
||||
T_DjiOpenArTouchAttribute touch_attr; /*!< Attributes related to touch interactions with the point */
|
||||
} T_DjiOpenArPoint;
|
||||
|
||||
/**
|
||||
* @brief Array of points
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint32_t len; /*!< Length of the array (number of points) */
|
||||
T_DjiOpenArPoint points[0]; /*!< 0 length implies dynamic allocation */
|
||||
} T_DjiOpenArPointArray;
|
||||
|
||||
/**
|
||||
* @biref AR Drawing Line
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
T_DjiOpenArIds ids; /*!< uuids for the AR line */
|
||||
T_DjiOpenArPointArray point_array; /*!< Array of points defining the line */
|
||||
} T_DjiOpenArLine;
|
||||
|
||||
/**
|
||||
* @brief AR Drawing Polygon
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
T_DjiOpenArIds ids; /*!< Unique identifiers for the AR polygon */
|
||||
T_DjiOpenArCoordinate normal_vector; /*!< Normal vector of the polygon surface */
|
||||
T_DjiOpenArPolygonFaceAttribute face; /*!< Face attributes of the polygon */
|
||||
T_DjiOpenArPolygonStrokeAttribute stroke; /*!< Stroke attributes of the polygon */
|
||||
T_DjiOpenArPointArray point_array; /*!< Array of points defining the polygon */
|
||||
} T_DjiOpenArPolygon;
|
||||
|
||||
/**
|
||||
* @brief AR Drawing Circle
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
T_DjiOpenArIds ids; /*!< Unique identifiers for the AR circle */
|
||||
float radius; /*!< Radius of the circle */
|
||||
T_DjiOpenArCoordinate center; /*!< Center coordinates of the circle */
|
||||
T_DjiOpenArCoordinate normal_vector; /*!< Normal vector of the circle's surface */
|
||||
T_DjiOpenArPolygonFaceAttribute face; /*!< Face attributes of the circle */
|
||||
T_DjiOpenArPolygonStrokeAttribute stroke; /*!< Stroke attributes of the circle */
|
||||
} T_DjiOpenArCircle;
|
||||
|
||||
/**
|
||||
* @brief AR Drawing 3D Cone Pivot Axis
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
T_DjiOpenArIds ids; /*!< Unique identifiers for the 3D cone */
|
||||
uint8_t show_enable; /*!< Flag indicating if the cone should be displayed (1) or not (0) */
|
||||
T_DjiOpenArCoordinate pivot; /*!< Center point of the cone */
|
||||
T_DjiOpenArCoordinate normal_vector; /*!< Normal vector for the cone's surface */
|
||||
} T_DjiOpenArPivotAxis;
|
||||
|
||||
/**
|
||||
* @brief eletion Entry for Specified Point, Face, Line, etc.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint32_t resource_id; /*!< Resource ID for the element to be deleted */
|
||||
uint32_t uuid_len; /*!< Length of the UUID array */
|
||||
uint32_t uuid_array[0]; /*!< Array of UUIDs to identify the elements to be deleted */
|
||||
} T_DjiOpenArDeletePointEntry;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint32_t uuid;
|
||||
} T_DjiOpenArDeleteCommonEntry;
|
||||
|
||||
/**
|
||||
* @brief Typedef for deletion of line entries
|
||||
*/
|
||||
typedef T_DjiOpenArDeleteCommonEntry T_DjiOpenArDeleteLineEntry;
|
||||
|
||||
/**
|
||||
* @brief Typedef for deletion of polygon entries
|
||||
*/
|
||||
typedef T_DjiOpenArDeleteCommonEntry T_DjiOpenArDeletePolygonEntry;
|
||||
|
||||
/**
|
||||
* @brief Typedef for deletion of circle entries
|
||||
*/
|
||||
typedef T_DjiOpenArDeleteCommonEntry T_DjiOpenArDeleteCircleEntry;
|
||||
|
||||
/**
|
||||
* @brief Typedef for deletion of pivot axis entries
|
||||
*/
|
||||
typedef T_DjiOpenArDeleteCommonEntry T_DjiOpenArDeletePovixAxisEntry;
|
||||
|
||||
/**
|
||||
* @brief Set the ar point.
|
||||
* @param metaData: the information for Ar point.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArSetPoint(const T_DjiOpenArPointArray* entry);
|
||||
|
||||
/**
|
||||
* @brief Update the ar point.
|
||||
* @param metaData: the information for Ar point.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArUpdatePoint(const T_DjiOpenArPointArray* entry);
|
||||
|
||||
/**
|
||||
* @brief Delete the ar point
|
||||
* @param metaData: the information for Ar point.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArDeletePoint(const T_DjiOpenArDeletePointEntry* entry);
|
||||
|
||||
/**
|
||||
* @brief Clear the ar point
|
||||
* @param metaData: the resource id for Ar point.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArClearPoint(uint32_t resource_id);
|
||||
|
||||
/**
|
||||
* @brief Set the ar line
|
||||
* @param metaData: the ar line information for setting.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArSetLine(const T_DjiOpenArLine* entry);
|
||||
|
||||
/**
|
||||
* @brief Update the ar line
|
||||
* @param metaData: The ar line information
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArUpdateLine(const T_DjiOpenArLine* entry);
|
||||
|
||||
/**
|
||||
* @brief Delete the ar line
|
||||
* @param metaData: The ar line entry for delete
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArDeleteLine(const T_DjiOpenArDeleteLineEntry* entry, uint32_t entry_len);
|
||||
|
||||
/**
|
||||
* @brief Clear the ar line.
|
||||
* @param metaData: The ar line information for clear.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArClearLine();
|
||||
|
||||
/**
|
||||
* @brief Set the ar polygon.
|
||||
* @param metaData: The ar polygon information for setting.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArSetPolygon(const T_DjiOpenArPolygon* entry);
|
||||
|
||||
/**
|
||||
* @brief Update the ar polygon.
|
||||
* @param metaData: The ar polygon information for update.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArUpdatePolygon(const T_DjiOpenArPolygon* entry);
|
||||
|
||||
/**
|
||||
* @brief Delete the ar polygon.
|
||||
* @param metaData: The polygon entry information for delete.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArDeletePolygon(const T_DjiOpenArDeletePolygonEntry* entry, uint32_t entry_len);
|
||||
|
||||
/**
|
||||
* @brief Clear the ar polygon.
|
||||
* @param metaData: none
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArClearPolygon();
|
||||
|
||||
/**
|
||||
* @brief Set the ar circle.
|
||||
* @param metaData: The ar circle information for setting.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArSetCircle(const T_DjiOpenArCircle* entry);
|
||||
|
||||
/**
|
||||
* @brief Update the ar circle.
|
||||
* @param metaData: The ar circle information for update.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArUpdateCircle(const T_DjiOpenArCircle* entry);
|
||||
|
||||
/**
|
||||
* @brief Delete the ar circle.
|
||||
* @param metaData: The ar circle information for delete.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArDeleteCircle(const T_DjiOpenArDeleteCircleEntry* entry, uint32_t entry_len);
|
||||
|
||||
/**
|
||||
* @brief Clear the ar circle.
|
||||
* @param metaData: The ar circle information for clear.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArClearCircle();
|
||||
|
||||
/**
|
||||
* @brief Set the pivot axis.
|
||||
* @param metaData: The pivot axis information for setting.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArSetPivotAxis(const T_DjiOpenArPivotAxis* entry);
|
||||
|
||||
/**
|
||||
* @brief Update the pivot axis.
|
||||
* @param metaData: The pivot axis information for update.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArUpdatePivotAxis(const T_DjiOpenArPivotAxis* entry);
|
||||
|
||||
/**
|
||||
* @brief Delete the pivot axis.
|
||||
* @param metaData: The pivot axis information for delete.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArDeletePivotAxis(const T_DjiOpenArDeletePovixAxisEntry* entry, uint32_t entry_len);
|
||||
|
||||
/**
|
||||
* @brief Clear the pivot axis.
|
||||
* @param metaData: none
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArClearPivotAxis();
|
||||
|
||||
/**
|
||||
* @brief Once entering this callback it is necessary to reflesh all AR drawings.
|
||||
* @param metaData: none
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
typedef void (*DjiLiveview_ArRefleshAllCallback)(void);
|
||||
|
||||
/**
|
||||
* @brief Register the ar refresh function.
|
||||
* @param metaData: The ar reflesh callback function.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArRegRefleshAllCallback(DjiLiveview_ArRefleshAllCallback callback);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // DJI_OPEN_AR_H
|
||||
@ -173,6 +173,8 @@ typedef struct {
|
||||
bool isShootingIntervalStart; /*!< Specifies if the camera is in interval shooting start status. This parameter is boolean type. */
|
||||
uint16_t currentPhotoShootingIntervalTimeInSeconds; /*!< Specifies the current interval shoot countdown time, the value is decreasing,
|
||||
* when the value equals to zero trigger the interval take photo, uint:s. */
|
||||
uint16_t currentPhotoShootingIntervalTimeInMs; /*!< Specifies the current interval shoot countdown time of millisecond part, the value is decreasing,
|
||||
* when the value equals to zero trigger the interval take photo, uint:ms. */
|
||||
uint16_t currentPhotoShootingIntervalCount; /*!< Specifies the current interval photo count, the value is decreasing step by one from
|
||||
* the setted count when interval taking photo */
|
||||
bool isRecording; /*!< Specifies if the camera is in recording status. This parameter is boolean type. */
|
||||
@ -841,7 +843,7 @@ T_DjiReturnCode DjiPayloadCamera_RegMediaDownloadPlaybackHandler(const T_DjiCame
|
||||
* @param len: length of data to be sent via data stream, and it must be less than or equal to 65000, unit: byte.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPayloadCamera_SendVideoStream(const uint8_t *data, uint16_t len);
|
||||
T_DjiReturnCode DjiPayloadCamera_SendVideoStream(const uint8_t *data, uint32_t len);
|
||||
|
||||
/**
|
||||
* @brief Get data transmission state of "videoStream" channel. User can use the state as base for controlling data
|
||||
|
||||
@ -39,6 +39,8 @@ extern "C" {
|
||||
#define DJI_PERCEPTION_INTRINSICS_PARAM_ARRAY_NUM 9
|
||||
#define DJI_PERCEPTION_ROTATION_PARAM_ARRAY_NUM 9
|
||||
#define DJI_PERCEPTION_TRANSLATION_PARAM_ARRAY_NUM 3
|
||||
#define DJI_PTS_NUM_PER_PKG 96
|
||||
#define DJI_LIDAR_PKG_BUFFER_NUM 564
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/**
|
||||
@ -71,6 +73,19 @@ typedef enum {
|
||||
RECTIFY_RIGHT_RIGHT = 26
|
||||
} E_DjiPerceptionCameraPosition;
|
||||
|
||||
/**
|
||||
* @bref Perception radar design location
|
||||
*/
|
||||
typedef enum {
|
||||
RADAR_POSITION_LEFT = 0,
|
||||
RADAR_POSITION_RIGHT = 1,
|
||||
RADAR_POSITION_DOWN =2,
|
||||
RADAR_POSITION_UP = 3,
|
||||
RADAR_POSITION_FRONT = 4,
|
||||
RADAR_POSITION_BACK =5,
|
||||
MAX_RADAR_NUM = 6,
|
||||
}E_DjiPerceptionRadarPosition;
|
||||
|
||||
#pragma pack(1)
|
||||
/**
|
||||
* @bref Perception camera ram image info
|
||||
@ -114,14 +129,217 @@ typedef struct {
|
||||
uint32_t directionNum;
|
||||
T_DjiPerceptionCameraParameters cameraParameters[IMAGE_MAX_DIRECTION_NUM];
|
||||
} T_DjiPerceptionCameraParametersPacket;
|
||||
|
||||
/**
|
||||
* @bref Perception Lidar data point info
|
||||
*/
|
||||
typedef struct{
|
||||
float x; /*!< unit: meters */
|
||||
float y; /*!< unit: meters */
|
||||
float z; /*!< unit: meters */
|
||||
uint8_t intensity;
|
||||
uint8_t label; /*!< Noise filtering results (0: obj; 1: noise; 2: unknow; 3: not_retuen ) */
|
||||
} T_DJIPerceptionLidarPoint;
|
||||
|
||||
/**
|
||||
* @bref Perception Lidar data header of each pkg
|
||||
*/
|
||||
typedef struct{
|
||||
uint16_t timeInterval; /*!< The point cloud sampling time (in 0.1us) */
|
||||
uint16_t dotNum; /*!< Current packet data field contains the number of points This field is not valid for non-repeat scans*/
|
||||
uint8_t dataType; /** dataType
|
||||
*
|
||||
* Bit Position (7-4) | Field Name | Description | Remarks
|
||||
* ------------------ | ------------ | -------------------- | -------------------------------------------------
|
||||
* 4-7 | echo_mode | Echo Mode | 0: Single echo mode
|
||||
* | | | 1: Dual echo mode
|
||||
* | | | 2: Triple echo mode
|
||||
* | | | 3: Quadruple echo mode
|
||||
* | | | 4: Quintuple echo mode
|
||||
*
|
||||
* Bit Position (3-0) | Field Name | Description | Remarks
|
||||
* ------------------ | ------------ | -------------------- | -------------------------------------------------
|
||||
* 0-3 | data_type | Data Type | 40: IMU Data
|
||||
* | | | 1: Point cloud data (rectangular, 32-bit)
|
||||
* | | | 2: Point cloud data (rectangular, 16-bit default)
|
||||
* | | | 3: Point cloud data (spherical)
|
||||
* | | | 4: Point cloud data (rectangular, 20-bit, in use)
|
||||
*/
|
||||
uint8_t timeType; /** timeType
|
||||
* Timestamp Type | Sync Source Type | Data Format | Description
|
||||
* -------------- | ------------------- | ------------- | -------------------------------------------------
|
||||
* 0 | No sync source, | uint64_t | Timestamp is radar uptime, unit: ns
|
||||
* | | |
|
||||
* 1 | gPTP/PTP sync, | uint64_t | Timestamp is master clock source time, unit: ns
|
||||
* | | |
|
||||
* 2 | PPS + ns time sync | uint64_t | Unit: ns
|
||||
* | | |
|
||||
* 3 | PPS + UTC | uint64_t | UTC format is:
|
||||
* | | struct | struct {
|
||||
* | | | uint8_t year;
|
||||
* | | | uint8_t mon;
|
||||
* | | | uint8_t day;
|
||||
* | | | uint8_t hour;
|
||||
* | | | uint32_t us_offset;
|
||||
* | | | };
|
||||
*/
|
||||
uint64_t timeStamp;
|
||||
}T_DJIPerceptionLidarDataHeader;
|
||||
|
||||
/**
|
||||
* @bref Perception Lidar data pkg
|
||||
*/
|
||||
typedef struct{
|
||||
T_DJIPerceptionLidarDataHeader header;
|
||||
T_DJIPerceptionLidarPoint points[DJI_PTS_NUM_PER_PKG];
|
||||
}T_DjiPerceptionLidarDecodePkg;
|
||||
|
||||
/**
|
||||
* @bref Perception Lidar data frame
|
||||
*/
|
||||
typedef struct{
|
||||
uint64_t timeStampNs; /*!< Timestamp of the first point of each packet */
|
||||
uint32_t frameCnt; /*!< in increasing order from zero */
|
||||
uint16_t pkgNum; /*!< Number of valid pkgs per frame */
|
||||
T_DjiPerceptionLidarDecodePkg pkgs[DJI_LIDAR_PKG_BUFFER_NUM];
|
||||
uint32_t poseTimeMs;
|
||||
uint16_t naviFlag; /** naviFlag:
|
||||
* Bit Position | Field Name | Description | Remarks
|
||||
* ------------ | ---------- | ------------------------------------------------ | -----------------------------------
|
||||
* 0 | vel_x | Horizontal x-axis velocity valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 1 | vel_y | Horizontal y-axis velocity valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 2 | vel_z | Vertical velocity valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 3 | pos_x | Horizontal x-axis position valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 4 | pos_y | Horizontal y-axis position valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 5 | pos_z | Vertical position valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 6 | dwn_vz | Ground speed valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 7 | dwn_pz | Ground elevation valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 8 | rtk_pxy | RTK horizontal valid flag (1 valid) | 1 - valid, 0 - invalid
|
||||
* 9 | rtk_pz | RTK vertical valid flag (1 valid) | 1 - valid, 0 - invalid
|
||||
* 10 | gns_ll | GPS horizontal valid flag (1 valid) | 1 - valid, vertical direction always invalid
|
||||
* 11 | fg_ok | FG estimate OK flag (1 valid) | 1 - valid, 0 - invalid
|
||||
* 12-15 | fg_st | FG mode (4 bits) | Modes:
|
||||
* | | | 0 - Random initialization
|
||||
* | | | 1 - Initialization with poor compass
|
||||
* | | | 2 - Initialization with good compass
|
||||
* | | | 3 - Magnetic inclination compensation
|
||||
* | | | 4 - Compass fix during takeoff
|
||||
* | | | 5 - Compass fix in the air
|
||||
* | | | 6 - Compass calibration fix
|
||||
* | | | 7 - Accelerometer alignment
|
||||
* | | | 8 - Speed alignment
|
||||
* | | | 9 - RTK heading alignment
|
||||
*/
|
||||
float naviPos[3]; /*!< UAV IMU to navigation coordinate system translation vector (xyz) */
|
||||
float naviQuat[4]; /*!< Quaternions from UAV IMU to navigation coordinate system */
|
||||
}T_DjiLidarFrame;
|
||||
|
||||
/**
|
||||
* @bref Radar data frame header
|
||||
*/
|
||||
typedef struct {
|
||||
uint16_t dataLen;
|
||||
uint8_t curPack; /*!< The current packet number, in the range of [1, pack_num]. */
|
||||
uint8_t packNum; /*!< Total number of current circle packets, starting from 1. */
|
||||
} T_DjiRadarDataHeader;
|
||||
|
||||
/**
|
||||
* @bref Radar information structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint64_t velocity :16; /**
|
||||
* Calculating the actual velocity:
|
||||
*
|
||||
* Actual velocity (m/s) = (Velocity - 32767) / 100
|
||||
*
|
||||
* Interpreting the results:
|
||||
* - If the result is > 0, it indicates that the object is moving closer to the target.
|
||||
* - If the result is < 0, it indicates that the object is moving away from the target.
|
||||
*/
|
||||
uint64_t snr :7; /*!< target SNR, in db, ranging from 0 to 127, with 0 being the null point or no echo point
|
||||
(base_noise calculation base_noise = energy / snr) */
|
||||
uint64_t beamAngle:10; /**
|
||||
* Beam emission angle value:
|
||||
* - Unit: 0.01 degrees
|
||||
* - Stored range: 0~1023
|
||||
* - Actual value range: [-45°, 45°]
|
||||
*
|
||||
* Conversion method:
|
||||
* - Divide stored value x by 10
|
||||
* - If x ≤ 450, the angle remains unchanged
|
||||
* - If x > 450, the angle is adjusted by subtracting 90
|
||||
*
|
||||
* Examples:
|
||||
* - Stored value of 449 yields an angle of 44.9° (449/10 = 44.9°)
|
||||
* - Stored value of 451 yields an angle of -44.9° (451/10 - 90 = -44.9°)
|
||||
* invalid in M400
|
||||
*/
|
||||
|
||||
uint64_t radarType:3; /*!< Radar numbe,is invalid in M400*/
|
||||
|
||||
uint64_t clitterFlag:1; /*!< Flag for clutter point in planar radar: 1 indicates a clutter point, 0 indicates a valid point */
|
||||
|
||||
uint64_t reserved :27;
|
||||
} T_DjiRadarBaseInfo;
|
||||
|
||||
/**
|
||||
* @bref The single point data structure of millimeter wave radar
|
||||
*/
|
||||
typedef struct {
|
||||
uint16_t azimuth; /*!
|
||||
* Target azimuth in radar coordinate system:
|
||||
* - Unit: 0.001 radian
|
||||
* - Value range: (0 to 2π) / 0.001
|
||||
* - Calculation method (azimuth/1000 - 2π)
|
||||
*/
|
||||
uint16_t elevation; /*!
|
||||
* Target pitch angle in radar coordinate system:
|
||||
* - Unit: 0.001 radian
|
||||
* - Value range: (0 to 2π) / 0.001
|
||||
* - Calculation method (elevation/1000 - 2π)
|
||||
*/
|
||||
uint16_t radius; /*!
|
||||
* Target radial distance in radar coordinate system:
|
||||
* - Unit: 0.01 meters
|
||||
* - Value range: 0 to 65553 (in steps of 0.01 meters)
|
||||
*/
|
||||
uint16_t ene; /*!
|
||||
* Radar target energy
|
||||
* - Actual value: energy / 100
|
||||
* - invalid in M400
|
||||
*/
|
||||
T_DjiRadarBaseInfo base_info;
|
||||
}T_DjiRadarCloudUnit;
|
||||
|
||||
/**
|
||||
* @bref Perception Radar data frame
|
||||
*/
|
||||
typedef struct {
|
||||
T_DjiRadarDataHeader headInfo;
|
||||
T_DjiRadarCloudUnit data[1];
|
||||
} T_DjiRadarDataFrame;
|
||||
|
||||
#pragma pack()
|
||||
|
||||
/**
|
||||
* @bref Callback type to receive stereo camera image
|
||||
* @note It is not recommended to perform blocking operations in the callback, as it may lead to data loss.
|
||||
*/
|
||||
typedef void(*DjiPerceptionImageCallback)(T_DjiPerceptionImageInfo imageInfo, uint8_t *imageRawBuffer,
|
||||
uint32_t bufferLen);
|
||||
|
||||
/**
|
||||
* @bref Callback type to receive radar data
|
||||
* @note It is not recommended to perform blocking operations in the callback, as it may lead to data loss.
|
||||
*/
|
||||
typedef void(*DjiPerceptionRadarCallback)(E_DjiPerceptionRadarPosition radarPosition, uint8_t *radarDataBuffer,
|
||||
uint32_t bufferLen);
|
||||
/**
|
||||
* @bref Callback type to process Lidar data
|
||||
* @note It is not recommended to perform blocking operations in the callback, as it may lead to data loss.
|
||||
*/
|
||||
typedef void(*DjiPerceptionLidarDataCallback)(uint8_t* lidarDataBuffer, uint32_t bufferLen);
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Initialize the perception module.
|
||||
@ -147,18 +365,44 @@ T_DjiReturnCode DjiPerception_SubscribePerceptionImage(E_DjiPerceptionDirection
|
||||
|
||||
/**
|
||||
* @brief Unsubscribe the raw image of both stereo cameras in the same direction.
|
||||
* @param direction: direction to specify the direction of the subscription. Ref to E_DjiPerceptionDirection
|
||||
* @param direction: direction to specify the direction of the subscription. Ref to E_DjiPerceptionDirection.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPerception_UnsubscribePerceptionImage(E_DjiPerceptionDirection direction);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get the internal and external parameters of all stereo cameras.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPerception_GetStereoCameraParameters(T_DjiPerceptionCameraParametersPacket *packet);
|
||||
|
||||
/**
|
||||
* @brief Subscribe the lidar data.
|
||||
* @param callback: callback to observer the radar data.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPerception_SubscribeLidarData(DjiPerceptionLidarDataCallback callback);
|
||||
|
||||
/**
|
||||
* @brief Unsubscribe the lidar data.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPerception_UnsubscribeLidarData(void);
|
||||
|
||||
/**
|
||||
* @brief Subscribe the lidar data of the position.
|
||||
* @param position: position the radar monted
|
||||
* @param callback callback to observer the radar data.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPerception_SubscribeRadarData(E_DjiPerceptionRadarPosition position, DjiPerceptionRadarCallback callback);
|
||||
|
||||
/**
|
||||
* @brief Unsubscribe the lidar data of the position.
|
||||
* @param position: position the radar monted
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPerception_UnsubscribeRadarData(E_DjiPerceptionRadarPosition position);
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -52,6 +52,11 @@ typedef void *T_DjiUsbBulkHandle;
|
||||
*/
|
||||
typedef void *T_DjiNetworkHandle;
|
||||
|
||||
/**
|
||||
* @brief Platform handle of i2c device operation.
|
||||
*/
|
||||
typedef void *T_DjiI2cHandle;
|
||||
|
||||
/**
|
||||
* @brief Platform handle of thread task operation.
|
||||
*/
|
||||
@ -104,6 +109,7 @@ typedef enum {
|
||||
typedef enum {
|
||||
DJI_HAL_USB_BULK_NUM_0 = 0,
|
||||
DJI_HAL_USB_BULK_NUM_1,
|
||||
DJI_HAL_USB_BULK_NUM_2,
|
||||
DJI_HAL_USB_BULK_NUM_MAX,
|
||||
} E_DjiHalUsbBulkNum;
|
||||
|
||||
@ -133,6 +139,11 @@ typedef struct {
|
||||
bool isDir;
|
||||
} T_DjiFileInfo;
|
||||
|
||||
typedef struct {
|
||||
uint16_t pid;
|
||||
uint16_t vid;
|
||||
} T_DjiHalUartDeviceInfo;
|
||||
|
||||
typedef struct {
|
||||
T_DjiReturnCode (*UartInit)(E_DjiHalUartNum uartNum, uint32_t baudRate, T_DjiUartHandle *uartHandle);
|
||||
|
||||
@ -143,6 +154,13 @@ typedef struct {
|
||||
T_DjiReturnCode (*UartReadData)(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen);
|
||||
|
||||
T_DjiReturnCode (*UartGetStatus)(E_DjiHalUartNum uartNum, T_DjiUartStatus *status);
|
||||
|
||||
/**
|
||||
* Get the device info of USB uart (virtual com or TTL-To-USB) which directly connected to UAV.
|
||||
* Use for SDK adapter type Eport V2 ribbon cable.
|
||||
* When using other types of interface, it is not necessary to implement this member function.
|
||||
*/
|
||||
T_DjiReturnCode (*UartGetDeviceInfo)(T_DjiHalUartDeviceInfo *deviceInfo);
|
||||
} T_DjiHalUartHandler;
|
||||
|
||||
typedef struct {
|
||||
@ -172,6 +190,11 @@ typedef struct {
|
||||
} usbNetAdapter;
|
||||
} T_DjiHalNetworkDeviceInfo;
|
||||
|
||||
typedef struct {
|
||||
uint32_t i2cSpeed;
|
||||
uint16_t devAddress;
|
||||
} T_DjiHalI2cConfig;
|
||||
|
||||
typedef struct {
|
||||
T_DjiReturnCode (*UsbBulkInit)(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHandle *usbBulkHandle);
|
||||
|
||||
@ -194,6 +217,18 @@ typedef struct {
|
||||
T_DjiReturnCode (*NetworkGetDeviceInfo)(T_DjiHalNetworkDeviceInfo *deviceInfo);
|
||||
} T_DjiHalNetworkHandler;
|
||||
|
||||
typedef struct {
|
||||
T_DjiReturnCode (*I2cInit)(T_DjiHalI2cConfig i2cConfig, T_DjiI2cHandle *i2cHandle);
|
||||
|
||||
T_DjiReturnCode (*I2cDeInit)(T_DjiI2cHandle i2cHandle);
|
||||
|
||||
T_DjiReturnCode (*I2cWriteData)(T_DjiI2cHandle i2cHandle, uint16_t devAddress, const uint8_t *buf,
|
||||
uint32_t len, uint32_t *realLen);
|
||||
|
||||
T_DjiReturnCode (*I2cReadData)(T_DjiI2cHandle i2cHandle, uint16_t devAddress, uint8_t *buf,
|
||||
uint32_t len, uint32_t *realLen);
|
||||
} T_DjiHalI2cHandler;
|
||||
|
||||
typedef struct {
|
||||
T_DjiReturnCode (*TaskCreate)(const char *name, void *(*taskFunc)(void *),
|
||||
uint32_t stackSize, void *arg, T_DjiTaskHandle *task);
|
||||
@ -314,11 +349,24 @@ T_DjiReturnCode DjiPlatform_RegHalUsbBulkHandler(const T_DjiHalUsbBulkHandler *h
|
||||
* sure that the feature is available after a successful registration.
|
||||
* @attention The interface needs to be called at the beginning of the application for registration, otherwise, the
|
||||
* subsequent functions will not work properly.
|
||||
* @param osalHandler: pointer to the handler for network handler interfaces by your platform.
|
||||
* @param halNetworkHandler: pointer to the handler for network handler interfaces by your platform.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPlatform_RegHalNetworkHandler(const T_DjiHalNetworkHandler *halNetworkHandler);
|
||||
|
||||
/**
|
||||
* @brief Register the handler for hal i2c master mode interfaces by your platform.
|
||||
* @note It should be noted that the interface in hal is written and tested well. Users need to implement all the
|
||||
* interfaces. Otherwise, the user interface cannot be successfully registered, and then the user interface is registered
|
||||
* through the interface. If the registration fails, it needs to be based on the return code. To judge the problem. Make
|
||||
* sure that the feature is available after a successful registration.
|
||||
* @attention The interface needs to be called at the beginning of the application for registration, otherwise, the
|
||||
* subsequent functions will not work properly.
|
||||
* @param halI2cHandler: pointer to the handler for hal i2c handler interfaces by your platform.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPlatform_RegHalI2cHandler(const T_DjiHalI2cHandler *halI2cHandler);
|
||||
|
||||
/**
|
||||
* @brief Register the handler for osal interfaces by your platform.
|
||||
* @note It should be noted that the interface in osal is written and tested well. Users need to implement all the
|
||||
@ -363,6 +411,12 @@ T_DjiHalUsbBulkHandler *DjiPlatform_GetHalUsbBulkHandler(void);
|
||||
*/
|
||||
T_DjiHalNetworkHandler *DjiPlatform_GetHalNetworkHandler(void);
|
||||
|
||||
/**
|
||||
* @brief Get the handler of i2c interfaces.
|
||||
* @return Pointer to i2c handler.
|
||||
*/
|
||||
T_DjiHalI2cHandler *DjiPlatform_GetHalI2cHandler(void);
|
||||
|
||||
/**
|
||||
* @brief Get the handler of file-system interfaces.
|
||||
* @return Pointer to file-system handler.
|
||||
|
||||
@ -45,6 +45,12 @@ typedef enum {
|
||||
DJI_POWER_MANAGEMENT_PIN_STATE_SET = 1, /*!< Specifies pin is in high level state. */
|
||||
} E_DjiPowerManagementPinState;
|
||||
|
||||
typedef enum {
|
||||
E_DJI_HIGH_POWER_VOLTAGE_13V6 = 0, /*!< Specifies pin is in 13.6V of voltage */
|
||||
E_DJI_HIGH_POWER_VOLTAGE_17V = 1, /*!< Specifies pin is in 17V of voltage */
|
||||
E_DJI_HIGH_POWER_VOLTAGE_24V = 2, /*!< Specifies pin is in 24V of voltage */
|
||||
} E_DjiHighPowerVoltage;
|
||||
|
||||
/**
|
||||
* @brief Prototype of callback function used to set level of high power application pin.
|
||||
* @param pinState: level state of pin to be set.
|
||||
@ -87,6 +93,17 @@ T_DjiReturnCode DjiPowerManagement_DeInit(void);
|
||||
*/
|
||||
T_DjiReturnCode DjiPowerManagement_ApplyHighPowerSync(void);
|
||||
|
||||
/**
|
||||
* @brief Apply high power from aircraft in blocking mode.
|
||||
* @details Before applying, user should register callback function used to set level state of high power application
|
||||
* pin using DjiPowerManagement_RegWriteHighPowerApplyPinCallback() function. After applying high power, power pin of
|
||||
* DJI adapter will output high power based predetermined specification.
|
||||
* @note Max execution time of this function is slightly larger than 600ms.
|
||||
* @param voltage: The voltage value will be applied to the VCC pin.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPowerManagement_ApplyHighPowerSyncV2(E_DjiHighPowerVoltage voltage);
|
||||
|
||||
/**
|
||||
* @brief Register callback function used to set level state of high power application pin. Must be called before
|
||||
* applying high power.
|
||||
@ -108,6 +125,15 @@ T_DjiReturnCode DjiPowerManagement_RegWriteHighPowerApplyPinCallback(DjiWriteHig
|
||||
*/
|
||||
T_DjiReturnCode DjiPowerManagement_RegPowerOffNotificationCallback(DjiPowerOffNotificationCallback callback);
|
||||
|
||||
/**
|
||||
* @brief manifold3 outputs high voltage to external devices
|
||||
* @param stat: true: output high voltage, false: output low voltage
|
||||
* @return Execution result.
|
||||
* @note The gpio12 of manifold3 should be pulled down before requesting a high voltage output.
|
||||
* @note This interface support on DJI manifold3.
|
||||
*/
|
||||
T_DjiReturnCode DjiPowerManagement_OutputHighPower(bool stat);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
77
Source/M300/PSDK_Qt/psdk_lib/include/dji_tethered_battery.h
Normal file
77
Source/M300/PSDK_Qt/psdk_lib/include/dji_tethered_battery.h
Normal file
@ -0,0 +1,77 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_tethered_battery.h
|
||||
* @brief This is the header file for "dji_tethered_battery.c", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2024 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 DJI’s 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_TETHERED_BATTERY_H
|
||||
#define DJI_TETHERED_BATTERY_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_typedef.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Tether line status.
|
||||
*/
|
||||
typedef struct {
|
||||
dji_f32_t totalLength; /*!< total length of tether line, range: 0-300, unit: meters. */
|
||||
dji_f32_t usedLength; /*!< used length of tether line, range: 0-300, unit: meters.
|
||||
This value must be less than or equal to the total length of tether line. */
|
||||
} T_DjiTetherLineStatus;
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Initialise tethered battery module
|
||||
* @note User should call this function before using tethered battery features.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiTetheredBattery_Init(void);
|
||||
|
||||
/**
|
||||
* @brief DeInitialize tethered battery module.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiTetheredBattery_DeInit(void);
|
||||
|
||||
/**
|
||||
* @brief Push the real-time tether line length to the Pilot2 for display.
|
||||
* @note It is recommended that the push frequency does not exceed the data update frequency. The maximum push
|
||||
* frequency should not exceed 10Hz.
|
||||
* @param tetherLineStatus: the tether line status.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiTetheredBattery_PushTetherLineStatus(T_DjiTetherLineStatus tetherLineStatus);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // DJI_TETHERED_BATTERY_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
@ -44,8 +44,9 @@ extern "C" {
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
#define DJI_PI (3.14159265358979323846f)
|
||||
#define DJI_FILE_NAME_SIZE_MAX 256
|
||||
#define DJI_FILE_MD5_LENGTH 16
|
||||
#define DJI_FILE_PATH_SIZE_MAX (DJI_FILE_NAME_SIZE_MAX + 256)
|
||||
#define DJI_IP_ADDR_STR_SIZE_MAX 15
|
||||
#define DJI_IP_ADDR_STR_SIZE_MAX 16
|
||||
#define DJI_MD5_BUFFER_LEN 16
|
||||
|
||||
#define DJI_SUBSCRIPTION_MODULE_INDEX_OFFSET 24u
|
||||
@ -58,6 +59,12 @@ extern "C" {
|
||||
(((((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)))
|
||||
|
||||
#define DJI_DATA_SUBSCRIPTION_TOPIC_GET_MODULE(topic) \
|
||||
((uint32_t)((topic & DJI_SUBSCRIPTION_MODULE_INDEX_MASK) >> DJI_SUBSCRIPTION_MODULE_INDEX_OFFSET))
|
||||
|
||||
#define DJI_DATA_SUBSCRIPTION_TOPIC_GET_CODE(topic) \
|
||||
((uint32_t)((topic & DJI_SUBSCRIPTION_TOPIC_CODE_MASK) >> DJI_SUBSCRIPTION_TOPIC_CODE_OFFSET))
|
||||
|
||||
/**
|
||||
* @brief Type define double as dji_f64_t.
|
||||
*/
|
||||
@ -76,7 +83,9 @@ 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_EXTENSION_LITE_PORT = 3
|
||||
DJI_MOUNT_POSITION_TYPE_EXTENSION_LITE_PORT = 3,
|
||||
DJI_MOUNT_POSITION_TYPE_EXTENSION_PORT_V2 = 4,
|
||||
DJI_MOUNT_POSITION_TYPE_MANIFOLD3_ONBOARD = 5,
|
||||
} E_DjiMountPositionType;
|
||||
|
||||
typedef enum {
|
||||
@ -84,8 +93,16 @@ typedef enum {
|
||||
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,
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO1 = DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1, /*!< Payload on Port: E1*/
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO2 = DJI_MOUNT_POSITION_PAYLOAD_PORT_NO2, /*!< Payload on Port: E2*/
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO3 = DJI_MOUNT_POSITION_PAYLOAD_PORT_NO3, /*!< Payload on Port: E3*/
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO4 = 4, /*!< Payload on Port: E4*/
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO5 = 5, /*!< Payload on Port: usb hub port1*/
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO6 = 6, /*!< Payload on Port: usb hub port2*/
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO7 = 7, /*!< Payload on Port: usb hub port3*/
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT,
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO8 = 8, /*!< Payload on Port: usb hub port4*/
|
||||
DJI_MOUNT_POSITION_EXTENSION_LITE_PORT,
|
||||
} E_DjiMountPosition;
|
||||
|
||||
typedef enum {
|
||||
@ -97,6 +114,9 @@ typedef enum {
|
||||
DJI_AIRCRAFT_SERIES_M350 = 5,
|
||||
DJI_AIRCRAFT_SERIES_M3D = 6,
|
||||
DJI_AIRCRAFT_SERIES_FC30 = 7,
|
||||
DJI_AIRCRAFT_SERIES_M4 = 8,
|
||||
DJI_AIRCRAFT_SERIES_M4D = 9,
|
||||
DJI_AIRCRAFT_SERIES_M400 = 10,
|
||||
} E_DjiAircraftSeries;
|
||||
|
||||
typedef enum {
|
||||
@ -110,9 +130,15 @@ typedef enum {
|
||||
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_M3TA = 80, /*!< Aircraft type is Mavic 3TA. */
|
||||
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. */
|
||||
DJI_AIRCRAFT_TYPE_M4T = 99, /*!< Aircraft type is Matrice 4T. */
|
||||
DJI_AIRCRAFT_TYPE_M4E = 990, /*!< Aircraft type is Matrice 4E. */
|
||||
DJI_AIRCRAFT_TYPE_M4TD = 100, /*!< Aircraft type is Matrice 4TD. */
|
||||
DJI_AIRCRAFT_TYPE_M4D = 1000, /*!< Aircraft type is Matrice 4D. */
|
||||
DJI_AIRCRAFT_TYPE_M400 = 103, /*!< Aircraft type is Matrice 400. */
|
||||
} E_DjiAircraftType;
|
||||
|
||||
/**
|
||||
@ -130,14 +156,20 @@ typedef enum {
|
||||
DJI_CAMERA_TYPE_P1 = 50, /*!< Camera type is P1. */
|
||||
DJI_CAMERA_TYPE_L1, /*!< Camera type is L1. */
|
||||
DJI_CAMERA_TYPE_L2 = 84, /*!< Camera type is L2. */
|
||||
DJI_CAMERA_TYPE_L3 = 117, /*!< Camera type is L3. */
|
||||
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_M3TA = 68, /*!< 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. */
|
||||
DJI_CAMERA_TYPE_M4T = 89, /*!< Camera type is M4T. */
|
||||
DJI_CAMERA_TYPE_M4E = 891, /*!< Camera type is M4E. */
|
||||
DJI_CAMERA_TYPE_M4TD = 90, /*!< Camera type is M4TD. */
|
||||
DJI_CAMERA_TYPE_M4D = 91, /*!< Camera type is M4D. */
|
||||
} E_DjiCameraType;
|
||||
|
||||
/**
|
||||
@ -248,7 +280,9 @@ 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, /*!< No external adapter is connected. */
|
||||
DJI_SDK_ADAPTER_TYPE_NONE = 3, /*!< don't have any adapter outside */
|
||||
DJI_SDK_ADAPTER_TYPE_SKYPORT_V3 = 4, /*!< SDK adapter type is Skyport V3 */
|
||||
DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE = 5, /*!< SDK adapter type is Eport V2 ribbon cable */
|
||||
} E_DjiSdkAdapterType;
|
||||
|
||||
typedef enum {
|
||||
@ -256,7 +290,15 @@ typedef enum {
|
||||
DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO1,
|
||||
DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO2,
|
||||
DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO3,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO1 = DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO1,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO2 = DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO2,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO3 = DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO3,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO4,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO5,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO6,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO7,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO8 = DJI_CHANNEL_ADDRESS_EXTENSION_PORT,
|
||||
DJI_CHANNEL_ADDRESS_MASTER_RC_APP,
|
||||
DJI_CHANNEL_ADDRESS_SLAVE_RC_APP,
|
||||
DJI_CHANNEL_ADDRESS_CLOUD_API,
|
||||
@ -278,6 +320,7 @@ typedef struct {
|
||||
uint8_t captureCount; /*!< Specifies the total capture count of interval settings.
|
||||
* 0: reserved, 1-254: specific number, 255: continuous capture until stopped. */
|
||||
uint16_t timeIntervalSeconds; /*!< Specifies the interval time between two captures, unit: s*/
|
||||
uint16_t timeIntervalMilliseconds; /*!< Specifies the interval time between two captures, unit: ms*/
|
||||
} T_DjiCameraPhotoTimeIntervalSettings;
|
||||
|
||||
/**
|
||||
|
||||
@ -33,11 +33,11 @@ extern "C" {
|
||||
#endif
|
||||
|
||||
/* 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 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 2090 /*!< DJI SDK version build info, when jenkins trigger build changes. Range from 0 to 65535. */
|
||||
#define DJI_VERSION_MAJOR 3 /*!< DJI SDK major version num, when have incompatible API changes. Range from 0 to 99. */
|
||||
#define DJI_VERSION_MINOR 15 /*!< 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_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 2318 /*!< DJI SDK version build info, when jenkins trigger build changes. Range from 0 to 65535. */
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
|
||||
308
Source/M300/PSDK_Qt/psdk_lib/include/dji_widget_manager.h
Normal file
308
Source/M300/PSDK_Qt/psdk_lib/include/dji_widget_manager.h
Normal file
@ -0,0 +1,308 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_widget_states_manager.h
|
||||
* @version V1.0.0
|
||||
* @date 2020/11/26
|
||||
* @brief This is the header file for "dji_widget_manager.h", 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 DJI’s 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_WIDGET_STATES_MANNAGER_H
|
||||
#define DJI_WIDGET_STATES_MANNAGER_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_typedef.h"
|
||||
#include "dji_widget.h"
|
||||
#include "dji_camera_manager.h"
|
||||
// #include "downloader/dji_download_file.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
#define WIDGET_MANAGER_MAX_FILE_NAME_LEN 32
|
||||
#define WIDGET_MANAGER_MAX_FILE_PATH_LEN 128
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Speaker system states.
|
||||
*/
|
||||
typedef enum {
|
||||
DJI_WIDGET_MGR_SPEAKER_SYSTEM_STATE_IDEL = 0,
|
||||
DJI_WIDGET_MGR_SPEAKER_SYSTEM_STATE_IN_TRANSMISSION = 1,
|
||||
DJI_WIDGET_MGR_SPEAKER_SYSTEM_STATE_PLAYING = 2,
|
||||
DJI_WIDGET_MGR_SPEAKER_SYSTEM_STATE_EXCEPTION = 3,
|
||||
DJI_WIDGET_MGR_SPEAKER_SYSTEM_STATE_IN_TTS_CONVERSION = 4,
|
||||
} E_DjiWidgetManagerSpeakerStates;
|
||||
|
||||
/**
|
||||
* @brief Speaker parameters.
|
||||
*/
|
||||
typedef enum {
|
||||
DJI_WIDGET_MGR_SPEAKER_PARAM_WORK_MODE = 0, /*!< The working mode fo the speaker */
|
||||
DJI_WIDGET_MGR_SPEAKER_PARAM_PALY_ACTION = 1, /*!< The playing action of the speaker */
|
||||
DJI_WIDGET_MGR_SPEAKER_PARAM_VOLUME = 2, /*!< The volume action of the speaker */
|
||||
DJI_WIDGET_MGR_SPEAKER_PARAM_PLAY_MODE = 3, /*!< The playing mode of the speaker */
|
||||
DJI_WIDGET_MGR_SPEAKER_PARAM_PLAY_FILE_NAME = 4, /*!<The name of the file to be played */
|
||||
} E_DjiWidgetManagerSpeakerPram;
|
||||
|
||||
/**
|
||||
* @brief Speaker audio bitrate
|
||||
*/
|
||||
typedef enum {
|
||||
DJI_SPEAKER_WIDGET_AUDIO_DECODE_BITRATE_8000 = 1,
|
||||
DJI_SPEAKER_WIDGET_AUDIO_DECODE_BITRATE_16000 = 2,
|
||||
DJI_SPEAKER_WIDGET_AUDIO_DECODE_BITRATE_24000 = 3,
|
||||
DJI_SPEAKER_WIDGET_AUDIO_DECODE_BITRATE_32000 = 4,
|
||||
DJI_SPEAKER_WIDGET_AUDIO_DECODE_BITRATE_48000 = 5,
|
||||
DJI_SPEAKER_WIDGET_AUDIO_DECODE_BITRATE_64000 = 6,
|
||||
} E_DjiWidgetManagerSpeakerAudoBitrate;
|
||||
|
||||
/**
|
||||
* @brief The type of audio file
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
DJI_SPEAKER_WIDGET_FILE_TYPE_TTS_TXT = 0,
|
||||
DJI_SPEAKER_WIDGET_FILE_TYPE_OPUS = 1,
|
||||
DJI_SPEAKER_WIDGET_FILE_TYPE_WAV = 2,
|
||||
} E_DjiWidgetManagerSpeakerFileType;
|
||||
|
||||
/**
|
||||
* @brief The states of widget.
|
||||
*/
|
||||
typedef struct{
|
||||
E_DjiWidgetType widgetType; /*!< The type fo the widget */
|
||||
uint8_t widgetIndex; /*!< The index fo the widget */
|
||||
int32_t widgetValue; /*!< The value fo the widget */
|
||||
} T_DjiWidgetStates;
|
||||
|
||||
/**
|
||||
* @brief The information of audio file.
|
||||
*/
|
||||
typedef struct{
|
||||
E_DjiWidgetManagerSpeakerFileType fileType; /*!< The type fo the audio file */
|
||||
E_DjiWidgetManagerSpeakerAudoBitrate fileBitrate; /*!< The bitrate fo the audio file */
|
||||
uint8_t uuid[WIDGET_MANAGER_MAX_FILE_NAME_LEN]; /*!< The uuid fo the audio file */
|
||||
uint8_t fileName[WIDGET_MANAGER_MAX_FILE_NAME_LEN]; /*!< The fileName fo the audio file */
|
||||
uint8_t filePath[WIDGET_MANAGER_MAX_FILE_PATH_LEN]; /*!< The absolute path to the audio file */
|
||||
} T_DjiSpeakerAudioFileInfo;
|
||||
|
||||
/**
|
||||
* @brief The states of the speaker's widget
|
||||
*/
|
||||
typedef struct {
|
||||
E_DjiWidgetSpeakerWorkMode workMode; /*!< The working mode of the speaker */
|
||||
E_DjiWidgetSpeakerPlayMode playMode; /*!< The playing mode of the speaker */
|
||||
uint8_t playVloume; /*!< The vloume of the speaker */
|
||||
E_DjiWidgetManagerSpeakerStates systemStates; /*!< The system states of the speaker */
|
||||
uint8_t playFileUuid[WIDGET_MANAGER_MAX_FILE_NAME_LEN]; /*!< The uuid of the playing file */
|
||||
uint8_t playFileName[WIDGET_MANAGER_MAX_FILE_NAME_LEN]; /*!< The name of the playing file */
|
||||
uint8_t playQuality; /*!< packet loss per second [0-255] mapped to 0%-100% */
|
||||
uint8_t actualVolume; /*!< The actual volume of the speaker */
|
||||
uint8_t limitVolumeOnTheGround; /*!< The limit volume when aircraft is on the ground */
|
||||
} T_DjiSpeakerWidgetStates;
|
||||
|
||||
/**
|
||||
* @brief Speaker parameters to be set
|
||||
*/
|
||||
typedef struct {
|
||||
E_DjiWidgetManagerSpeakerPram paramType; /*!< Type of speaker parameter to set */
|
||||
union {
|
||||
uint8_t value;
|
||||
uint8_t fileName[32];
|
||||
}data;
|
||||
} T_DjiSpeakerWidgetStatesParam;
|
||||
|
||||
/**
|
||||
* @brief Widget file information
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t fileSize;
|
||||
uint32_t fileIndex;
|
||||
char fileName[DJI_FILE_NAME_SIZE_MAX];
|
||||
} T_DjiWidgetManagerFileInfo;
|
||||
|
||||
/**
|
||||
* @brief The list of widget file information
|
||||
*/
|
||||
typedef struct{
|
||||
uint8_t totalCount;
|
||||
T_DjiWidgetManagerFileInfo *fileListInfo;
|
||||
} T_DjiWidgetManagerFileList;
|
||||
|
||||
/**
|
||||
* @brief Widget file download process information
|
||||
*/
|
||||
typedef struct {
|
||||
E_DjiDownloadFileEvent downloadFileEvent; /*!< Download Event Type */
|
||||
E_DjiMountPosition position; /*!< The position of the payload of the downloaded file */
|
||||
uint32_t fileIndex;
|
||||
uint32_t fileSize;
|
||||
dji_f32_t progressInPercent;
|
||||
} T_DjiDownloadWidgetFileInfo;
|
||||
|
||||
/**
|
||||
* @brief Type of callback function to receive widget states.
|
||||
* @param position: The position of the payload from which the widget states comes.
|
||||
* @param statesData: widgets states of widgets.
|
||||
* @param widgetNum: Number of widgets.
|
||||
* @note It is not recommended to perform blocking operations in the callback, as it may lead to data loss.
|
||||
* @return Execution result.
|
||||
*/
|
||||
typedef void (*RecvWidgetStatesCallback)(E_DjiMountPosition position, T_DjiWidgetStates *statesData, uint8_t widgetNum);
|
||||
|
||||
/**
|
||||
* @brief Type of callback function to receive speaker widget states.
|
||||
* @param position: The position of the speaker from which the widget states comes.
|
||||
* @param statesData: widgets states of speaker.
|
||||
* @note It is not recommended to perform blocking operations in the callback, as it may lead to data loss.
|
||||
* @return Execution result.
|
||||
*/
|
||||
typedef void (*RecvSpeakerStatesCallback)(E_DjiMountPosition position, T_DjiSpeakerWidgetStates *speakerStates);
|
||||
|
||||
/**
|
||||
* @brief Types of callback functions that handle downloading widget file data.
|
||||
* @param packetInfo: Widget file download process information.
|
||||
* @param data: Download raw data.
|
||||
* @param len: length of data.
|
||||
* @note It is not recommended to perform blocking operations in the callback, as it may lead to data loss.
|
||||
* @return Execution result.
|
||||
*/
|
||||
typedef T_DjiReturnCode (*DjiWidgetDownloadFileDataCallback)(T_DjiDownloadWidgetFileInfo packetInfo,
|
||||
const uint8_t *data,
|
||||
uint16_t dataLen);
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Initialize the widget manager module.
|
||||
* @note The interface initialization needs to be after DjiCore_Init.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_Init();
|
||||
|
||||
/**
|
||||
* @brief Denitialize the widget manager module.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_DeInit();
|
||||
|
||||
/**
|
||||
* @brief Subscribe to the widget states of a Payload.
|
||||
* @param position: the position of the target payload.
|
||||
* @param recvStatesCallback: the callback function to recv the widget states.
|
||||
* @note Use this interface to be notified when the states of the target payload's widget changes.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_SubscribePayloadWidgetStates(E_DjiMountPosition position,
|
||||
RecvWidgetStatesCallback recvStatesCallback);
|
||||
|
||||
/**
|
||||
* @brief Unsubscribe to the widget states of a Payload.
|
||||
* @param position: the position of the target payload.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_UnsubscribePayloadWidgetStates(E_DjiMountPosition position);
|
||||
|
||||
/**
|
||||
* @brief Set the widge state of the target payload.
|
||||
* @param position: the position of the target payload.
|
||||
* @param states: Widget parameters to be set.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_SetWidgetState(E_DjiMountPosition position, T_DjiWidgetStates states);
|
||||
|
||||
/**
|
||||
* @brief Subscribe to the widget states of a speaker.
|
||||
* @param position: the position of the target speaker.
|
||||
* @param recvStatesCallback: the callback function to recv the widget states.
|
||||
* @note Use this interface to be notified when the states of the target speaker's widget changes.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_SubscribeSpeakerStates(E_DjiMountPosition position,
|
||||
RecvSpeakerStatesCallback recvStatesCallback);
|
||||
|
||||
/**
|
||||
* @brief Unsubscribe to the widget states of a speaker.
|
||||
* @param position: the position of the target speaker.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_UnsubscribeSpeakerStates(E_DjiMountPosition position);
|
||||
|
||||
/**
|
||||
* @brief Set the widge state of the target speaker.
|
||||
* @param position: the position of the target payload.
|
||||
* @param states: Widget parameters to be set.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_SetSpeakertState(E_DjiMountPosition position,
|
||||
T_DjiSpeakerWidgetStatesParam *states);
|
||||
|
||||
/**
|
||||
* @brief Transferring audio files to speaker.
|
||||
* @param position: the position of the target speaker.
|
||||
* @param audioFileInfo: Audio file description information.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_SendSpeakerAudioData(E_DjiMountPosition position,
|
||||
T_DjiSpeakerAudioFileInfo *audioFileInfo);
|
||||
|
||||
/**
|
||||
* @brief Download the list of widget files for the target payload
|
||||
* @param position: the position of the target speaker.
|
||||
* @param fileList: Information on the list of files obtained from the download.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_WidgetDownloadFileList(E_DjiMountPosition position,
|
||||
T_DjiWidgetManagerFileList *fileList) ;
|
||||
|
||||
/**
|
||||
* @brief Registering callback functions for downloading widget files
|
||||
* @param position: The position of the target speaker.
|
||||
* @param recvFileCallback: The callback to receive the downloaded widget file.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_RegDownloadFileDataCallback(E_DjiMountPosition position,
|
||||
DjiWidgetDownloadFileDataCallback recvFileCallback);
|
||||
|
||||
/**
|
||||
* @brief Unregistering callback functions for downloading widget files.
|
||||
* @param position: The position of the target speaker.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_UnRegDownloadFileDataCallback(E_DjiMountPosition position);
|
||||
|
||||
/**
|
||||
* @brief Download the corresponding widget file on the target payload according to the file index.
|
||||
* @param position: The position of the target speaker.
|
||||
* @param fileIndex: The index of the file that will be downloaded
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_DownloadFileByIndex(E_DjiMountPosition position, uint32_t fileIndex);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // DJI_WIDGET_STATES_MANNAGER_H
|
||||
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
Reference in New Issue
Block a user