Skip to content

Commit

Permalink
Merge pull request #99 from dji-sdk/release/v3.5
Browse files Browse the repository at this point in the history
NEW: release DJI Payload-SDK version 3.5
  • Loading branch information
dji-dev committed May 18, 2023
2 parents cae3123 + caa1513 commit 9f1e4cc
Show file tree
Hide file tree
Showing 81 changed files with 558 additions and 176 deletions.
4 changes: 2 additions & 2 deletions LICENSE.txt
Expand Up @@ -316,7 +316,7 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in
│   │   │   │   ├── hal_uart.h
│   │   │   │   ├── hal_usb_bulk.c
│   │   │   │   └── hal_usb_bulk.h
│   │   │   └── nvidia_jeston
│   │   │   └── nvidia_jetson
│   │   │   ├── application
│   │   │   │   ├── dji_sdk_app_info.h
│   │   │   │   ├── dji_sdk_config.h
Expand Down Expand Up @@ -497,7 +497,7 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in
│   │   ├── hal_uart.h
│   │   ├── hal_usb_bulk.c
│   │   └── hal_usb_bulk.h
│   └── nvidia_jeston
│   └── nvidia_jetson
│   ├── application
│   │   ├── application.cpp
│   │   ├── application.hpp
Expand Down
49 changes: 17 additions & 32 deletions README.md
@@ -1,6 +1,6 @@
# DJI Payload SDK (PSDK)

![](https://img.shields.io/badge/version-V3.4.0-pink.svg)
![](https://img.shields.io/badge/version-V3.5.0-yellow.svg)
![](https://img.shields.io/badge/platform-linux_|_rtos-green.svg)
![](https://img.shields.io/badge/license-MIT-blue.svg)

Expand All @@ -23,37 +23,22 @@ to get the latest version information.

## Latest Release

PSDK 3.4.0 was released on 18 April 2023. This version of Payload SDK mainly add some new features support and fixed
some bugs. Please refer to the release notes for detailed changes list.

* Added support for SDK interconnection on M30/M30T
* Added support for downloading camera media files on M3E/M3T
* Added support for infrared temperature in camera management on M30T/M3T
* Added support for waypoint action status push on M30/M30T and M3E/M3T
* Added support for custom HMS function on all models
* Added support for custom device version number and serial number on all models
* Added support for subscribing to video stream request I-frame on all models
* Added support for obtaining H20N laser distance measurement data camera management on M300 RTK
* Added support for controlling H20N infrared zoom in camera management on M300 RTK
* Added support for subscribing perception grayscale image by Ethernet on M30/M30T and M3E/M3T
* Added support for downloading camera media files by Ethernet on M30/M30T and M3E/M3T
* Added support for Nvidia Jeston series development boards sample
* Added support for H20/H20T model files
* Fixed issue with unsuccessful initialization in USB single Bulk mode on M30/M30T and M3E/M3T
* Fixed issue with unstable data transmission OSDK expansion port to PSDK port for passing through small data on M300 RTK
* Fixed issue with third-party camera function causing payload disconnection due to deleting all media files in certain platforms on M300 RTK
* Fixed issue with gimbal mode abnormal setting in gimbal management on M300 RTK
* Fixed issue with deleting L1 camera media files in camera management on M300 RTK
* Fixed issue with abnormal triggering of text input box widget function in RTOS platform on M300 RTK
* Fixed issue with abnormal payload power supply during hot plugging in some scenarios in RTOS platform on M3E/M3T
* Fixed issue with CPU loading abnormal usage due to multiple video stream subscriptions on M30/M30T
* Fixed issue with occasional payload negotiation failure on M30/M30T and M3E/M3T
* Fixed issue with obtaining camera work mode on M30/M30T and M3E/M3T
* Fixed issue with obtaining camera zoom parameters on M30/M30T and M3E/M3T
* Fixed issue with altitude and distance limitations when using joystick function in some scenarios on all models
* Fixed some memory leak issues
* Optimized camera management C++ Sample support
* Optimized gimbal management C++ Sample support
PSDK 3.5.0 was released on 18 May 2023. This version of Payload SDK mainly add support for M350 RTK, also add some new features support and fixed some bugs.
Please refer to the release notes for detailed changes list.

* Added support for new drone model Matrice 350 RTK
* Matrice 300 RTK added support for DJI RC Plus
* Added support for downloading media files in pieces on all drone models
* Added support for Osal get random number callback interface on all drone model
* Fixed issue with the black screen problem when uses third-party camera to playback video on M300 RTK and DJI smart controller screen combination
* Fixed issue with failure of subscribing L1 camera code stream on M300 RTK
* Fixed issue with failure of subscribing main camera code stream in dual control mode on M300 RTK
* Fixed issue with local upgrade function of RTOS platform on Mavic 3E/3T
* Fixed issue with the initialization failure of using PSDK Payload device and millimeter wave radar on M300 RTK
* Fixed issue with custom HMS function on M300 RTK and X-Port combination
* Fixed issue with invalid TTS option of speaker widget on M300 RTK
* Fixed issue with downloading file list with high probability of failure when the camera photos are over 400 on M300 RTK
* Fixed some of the memory leaks

## License

Expand Down
23 changes: 23 additions & 0 deletions psdk_lib/include/dji_camera_manager.h
Expand Up @@ -442,6 +442,12 @@ typedef enum {
DJI_CAMERA_MANAGER_RECORDING_CONTROL_RESUME = 3,
} E_DjiCameraManagerRecordingControl;

typedef enum {
DJI_CAMERA_MANAGER_FILE_LIST_COUNT_60_PER_SLICE = 60,
DJI_CAMERA_MANAGER_FILE_LIST_COUNT_120_PER_SLICE = 120,
DJI_CAMERA_MANAGER_FILE_LIST_COUNT_ALL_PER_SLICE = 0xFFFF,
} E_DjiCameraManagerFileListCountPerSlice;

typedef struct {
uint8_t firmware_version[4];
} T_DjiCameraManagerFirmwareVersion;
Expand Down Expand Up @@ -500,6 +506,11 @@ typedef struct {
T_DjiCameraManagerFileListInfo *fileListInfo;
} T_DjiCameraManagerFileList;

typedef struct {
uint16_t sliceStartIndex;
E_DjiCameraManagerFileListCountPerSlice countPerSlice;
} T_DjiCameraManagerSliceConfig;

typedef enum {
DJI_DOWNLOAD_FILE_EVENT_START,
DJI_DOWNLOAD_FILE_EVENT_TRANSFER,
Expand Down Expand Up @@ -1011,6 +1022,18 @@ T_DjiReturnCode DjiCameraManager_StopRecordVideo(E_DjiMountPosition position);
*/
T_DjiReturnCode DjiCameraManager_DownloadFileList(E_DjiMountPosition position, T_DjiCameraManagerFileList *fileList);

/**
* @brief Download selected camera media file list by slices.
* @note The interface is a synchronous interface, which occupies more CPU resources when using it.
* If the download file fails, the timeout time is 3S.
* @param position: the mount position of the camera
* @param sliceConfig: the slices config for downloading file list
* @param fileList: the pointer to the downloaded camera file list
* @return Execution result.
*/
T_DjiReturnCode DjiCameraManager_DownloadFileListBySlices(E_DjiMountPosition position,
T_DjiCameraManagerSliceConfig sliceConfig,
T_DjiCameraManagerFileList *fileList);
/**
* @brief Regsiter selected camera download file data callback,
* @param position: the mount position of the camera
Expand Down
16 changes: 8 additions & 8 deletions psdk_lib/include/dji_fc_subscription.h
Expand Up @@ -361,8 +361,8 @@ typedef enum {
DJI_FC_SUBSCRIPTION_TOPIC_STATUS_MOTOR_START_ERROR = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC,
31),
/*!
* @brief Battery information topic name. Please refer to ::T_DjiFcSubscriptionBatteryInfo for information about data structure.
* @datastruct \ref T_DjiFcSubscriptionBatteryInfo
* @brief Battery information topic name. Please refer to ::T_DjiFcSubscriptionWholeBatteryInfo for information about data structure.
* @datastruct \ref T_DjiFcSubscriptionWholeBatteryInfo
*/
DJI_FC_SUBSCRIPTION_TOPIC_BATTERY_INFO = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 32),
/*!
Expand Down Expand Up @@ -977,13 +977,13 @@ typedef struct BatteryWholeInfo {
typedef struct BatterySingleInfo {
uint8_t reserve;
uint8_t batteryIndex;
int32_t currentVoltage; /*!< uint:mV. */
int32_t currentElectric; /*!< uint:mA. */
uint32_t fullCapacity; /*!< uint:mAh. */
uint32_t remainedCapacity; /*!< uint:mAh. */
int16_t batteryTemperature; /*!< uint:℃. */
int32_t currentVoltage; /*!< uint: mV. */
int32_t currentElectric; /*!< uint: mA. */
uint32_t fullCapacity; /*!< uint: mAh. */
uint32_t remainedCapacity; /*!< uint: mAh. */
int16_t batteryTemperature; /*!< uint: 0.1℃. */
uint8_t cellCount;
uint8_t batteryCapacityPercent; /*!< uint:%. */
uint8_t batteryCapacityPercent; /*!< uint: %. */
T_DjiFcSubscriptionSingleBatteryState batteryState;
uint8_t reserve1;
uint8_t reserve2;
Expand Down
1 change: 0 additions & 1 deletion psdk_lib/include/dji_flight_controller.h
Expand Up @@ -76,7 +76,6 @@ typedef enum {
*/
typedef enum {
DJI_FLIGHT_CONTROLLER_ENABLE_EMERGENCY_STOP_MOTOR = 0x01, /*!< Execute emergency-stop-motor action */
DJI_FLIGHT_CONTROLLER_DISABLE_EMERGENCY_STOP_MOTOR = 0x02 /*!< Cancel emergency-stop-motor status */
} E_DjiFlightControllerEmergencyStopMotor;

/**
Expand Down
7 changes: 6 additions & 1 deletion psdk_lib/include/dji_platform.h
Expand Up @@ -89,11 +89,14 @@ typedef enum {
* Baud rate support list on M300 RTK Extension Port: 115200, 230400, 460800, 921600, 1000000.
* Baud rate support list on M30/M30T: 115200, 230400, 460800, 921600, 1000000.
* Baud rate support list on M3E/M3T: 921600.
* Baud rate support list on M350 RTK Payload Port: 115200, 230400, 460800, 921600.
* Baud rate support list on M350 RTK Extension Port: 115200, 230400, 460800, 921600, 1000000.
* */
DJI_HAL_UART_NUM_0,
/**
* Only support on M300 RTK Extension Port by USB virtual serial port, such as /dev/ttyACM0.
* Only support on M300/M350 RTK Extension Port by USB virtual serial port, such as /dev/ttyACM0.
* Baud rate support list on M300 RTK Extension Port: 921600.
* Baud rate support list on M350 RTK Extension Port: 921600.
* */
DJI_HAL_UART_NUM_1,
} E_DjiHalUartNum;
Expand Down Expand Up @@ -221,6 +224,8 @@ typedef struct {

T_DjiReturnCode (*GetTimeUs)(uint64_t *us);

T_DjiReturnCode (*GetRandomNum)(uint16_t *randomNum);

void *(*Malloc)(uint32_t size);

void (*Free)(void *ptr);
Expand Down
6 changes: 6 additions & 0 deletions psdk_lib/include/dji_power_management.h
Expand Up @@ -71,6 +71,12 @@ typedef T_DjiReturnCode (*DjiPowerOffNotificationCallback)(bool *powerOffPrepara
*/
T_DjiReturnCode DjiPowerManagement_Init(void);

/**
* @brief DeInitialise power management module, and user should call this function before using power management features.
* @return Execution result.
*/
T_DjiReturnCode DjiPowerManagement_DeInit(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
Expand Down
4 changes: 3 additions & 1 deletion psdk_lib/include/dji_typedef.h
Expand Up @@ -83,7 +83,7 @@ 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_PORT = 4,
} E_DjiMountPosition;

typedef enum {
Expand All @@ -92,6 +92,7 @@ typedef enum {
DJI_AIRCRAFT_SERIES_M300 = 2,
DJI_AIRCRAFT_SERIES_M30 = 3,
DJI_AIRCRAFT_SERIES_M3 = 4,
DJI_AIRCRAFT_SERIES_M350 = 5,
} E_DjiAircraftSeries;

typedef enum {
Expand All @@ -104,6 +105,7 @@ typedef enum {
DJI_AIRCRAFT_TYPE_M30T = 68, /*!< Aircraft type is Matrice 30T. */
DJI_AIRCRAFT_TYPE_M3E = 77, /*!< Aircraft type is Mavic 3E. */
DJI_AIRCRAFT_TYPE_M3T = 79, /*!< Aircraft type is Mavic 3T. */
DJI_AIRCRAFT_TYPE_M350_RTK = 89, /*!< Aircraft type is Matrice 350 RTK. */
} E_DjiAircraftType;

/**
Expand Down
4 changes: 2 additions & 2 deletions psdk_lib/include/dji_version.h
Expand Up @@ -34,10 +34,10 @@ extern "C" {

/* Exported constants --------------------------------------------------------*/
#define DJI_VERSION_MAJOR 3 /*!< DJI SDK major version num, when have incompatible API changes. Range from 0 to 99. */
#define DJI_VERSION_MINOR 4 /*!< DJI SDK minor version num, when add functionality in a backwards compatible manner changes. Range from 0 to 99. */
#define DJI_VERSION_MINOR 5 /*!< DJI SDK minor version num, when add functionality in a backwards compatible manner changes. Range from 0 to 99. */
#define DJI_VERSION_MODIFY 0 /*!< DJI SDK modify version num, when have backwards compatible bug fixes changes. Range from 0 to 99. */
#define DJI_VERSION_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 1749 /*!< DJI SDK version build info, when jenkins trigger build changes. Range from 0 to 65535. */
#define DJI_VERSION_BUILD 1764 /*!< DJI SDK version build info, when jenkins trigger build changes. Range from 0 to 65535. */

/* Exported types ------------------------------------------------------------*/

Expand Down
Binary file modified psdk_lib/lib/aarch64-himix100-linux-gcc/libpayloadsdk.a
Binary file not shown.
Binary file modified psdk_lib/lib/aarch64-linux-gnu-gcc/libpayloadsdk.a
Binary file not shown.
Binary file modified psdk_lib/lib/arm-himix100-linux-gcc/libpayloadsdk.a
Binary file not shown.
Binary file modified psdk_lib/lib/arm-himix200-linux-gcc/libpayloadsdk.a
Binary file not shown.
Binary file modified psdk_lib/lib/arm-hisiv300-linux-gcc/libpayloadsdk.a
Binary file not shown.
Binary file modified psdk_lib/lib/arm-hisiv400-linux-gcc/libpayloadsdk.a
Binary file not shown.
Binary file modified psdk_lib/lib/arm-hisiv500-linux-gcc/libpayloadsdk.a
Binary file not shown.
Binary file modified psdk_lib/lib/arm-hisiv600-linux-gcc/libpayloadsdk.a
Binary file not shown.
Binary file modified psdk_lib/lib/arm-linux-gnueabi-gcc/libpayloadsdk.a
Binary file not shown.
Binary file modified psdk_lib/lib/arm-linux-gnueabihf-gcc/libpayloadsdk.a
Binary file not shown.
Binary file modified psdk_lib/lib/arm-none-eabi-gcc/libpayloadsdk.a
Binary file not shown.
Binary file modified psdk_lib/lib/armcc_cortex-m4/libpayload.lib
Binary file not shown.
Binary file modified psdk_lib/lib/x86_64-linux-gnu-gcc/libpayloadsdk.a
Binary file not shown.
Binary file modified psdk_lib/lib/xtensa-esp32-elf-gcc/libpayloadsdk.a
Binary file not shown.
Expand Up @@ -50,6 +50,7 @@ static const char *s_cameraManagerSampleSelectList[] = {
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_INTERVAL_PHOTO] = "Shoot interval photo |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_RECORD_VIDEO] = "Record video |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_DOWNLOAD_AND_DELETE_MEDIA_FILE] = "Download and delete media file |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_DOWNLOAD_FILE_LIST_BY_SLICES] = "Download file list by slices |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_THERMOMETRY] = "Thermometry test |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_GET_LIDAR_RANGING_INFO] = "Get lidar ranging info |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_IR_CAMERA_ZOOM_PARAM] = "Set ir camera zoom param |",
Expand Down Expand Up @@ -120,8 +121,7 @@ void DjiUser_RunCameraManagerSample(void)
if (posNum > 3 || posNum < 1) {
USER_LOG_ERROR("Input mount position is invalid");
continue;
}
else {
} else {
break;
}
}
Expand All @@ -140,15 +140,15 @@ void DjiUser_RunCameraManagerSample(void)
return;
}

sampleSelectNum = atoi(sampleSelectStr.c_str());
sampleSelectNum = atoi(sampleSelectStr.c_str());

if (sampleSelectNum < 0 ||
sampleSelectNum >= (int)E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_INDEX_MAX) {
sampleSelectNum >= (int) E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_INDEX_MAX) {
USER_LOG_ERROR("Input camera sample is invalid");
continue;
}

cameraSample = (E_DjiTestCameraManagerSampleSelect)sampleSelectNum;
cameraSample = (E_DjiTestCameraManagerSampleSelect) sampleSelectNum;

cout << "Start test: position " << cameraMountPosition
<< ", sample " << cameraSample << endl;
Expand Down
Expand Up @@ -88,6 +88,7 @@ void DjiUser_RunGimbalManagerSample(void)
if (mountPosition == 'q') {
return;
}

if (mountPosition > '3' || mountPosition < '1') {
USER_LOG_ERROR("Input mount position is invalid");
goto start;
Expand Down Expand Up @@ -126,4 +127,4 @@ void DjiTest_GimbalManagerShowSampleSelectList(const char **SampleList, uint8_t
std::cout << SampleList[i] << std::endl;
}
}
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
Expand Up @@ -48,4 +48,5 @@ void DjiUser_RunGimbalManagerSample(void);
#endif

#endif // TEST_GIMBAL_ENTRY_H
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/

@@ -1,4 +1,4 @@
/**
/**
********************************************************************
* @file test_perception_entry.cpp
* @brief
Expand Down Expand Up @@ -358,13 +358,6 @@ static void *DjiTest_StereoImagesDisplayTask(void *arg)
pack->gotData = false;
osalHandler->MutexUnlock(pack->mutex);

/*! Using Opencv display here */
if (strstr(nameStr, "_l")) {
cv::moveWindow(nameStr, 200, 0);
} else {
cv::moveWindow(nameStr, (200 + (int) pack->info.rawInfo.width), 0);
}

if (i < USER_PERCEPTION_DIRECTION_NUM) {
/*! Calculate frame rate */
timeNow[i] = (double) cv::getTickCount();
Expand Down
32 changes: 29 additions & 3 deletions samples/sample_c++/platform/linux/common/osal/osal.c
Expand Up @@ -98,6 +98,10 @@ T_DjiReturnCode Osal_MutexCreate(T_DjiMutexHandle *mutex)
{
int result;

if (!mutex) {
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}

*mutex = malloc(sizeof(pthread_mutex_t));
if (*mutex == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_MEMORY_ALLOC_FAILED;
Expand All @@ -118,7 +122,11 @@ T_DjiReturnCode Osal_MutexCreate(T_DjiMutexHandle *mutex)
*/
T_DjiReturnCode Osal_MutexDestroy(T_DjiMutexHandle mutex)
{
int result;
int result = 0;

if (!mutex) {
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}

result = pthread_mutex_destroy(mutex);
if (result != 0) {
Expand All @@ -136,8 +144,13 @@ T_DjiReturnCode Osal_MutexDestroy(T_DjiMutexHandle mutex)
*/
T_DjiReturnCode Osal_MutexLock(T_DjiMutexHandle mutex)
{
int result = pthread_mutex_lock(mutex);
int result = 0;

if (!mutex) {
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}

result = pthread_mutex_lock(mutex);
if (result != 0) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
Expand All @@ -152,8 +165,13 @@ T_DjiReturnCode Osal_MutexLock(T_DjiMutexHandle mutex)
*/
T_DjiReturnCode Osal_MutexUnlock(T_DjiMutexHandle mutex)
{
int result = pthread_mutex_unlock(mutex);
int result = 0;

if (!mutex) {
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}

result = pthread_mutex_unlock(mutex);
if (result != 0) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
Expand Down Expand Up @@ -308,6 +326,14 @@ T_DjiReturnCode Osal_GetTimeUs(uint64_t *us)
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}

T_DjiReturnCode Osal_GetRandomNum(uint16_t *randomNum)
{
srand(time(NULL));
*randomNum = random() % 65535;

return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}

void *Osal_Malloc(uint32_t size)
{
return malloc(size);
Expand Down
1 change: 1 addition & 0 deletions samples/sample_c++/platform/linux/common/osal/osal.h
Expand Up @@ -65,6 +65,7 @@ T_DjiReturnCode Osal_SemaphorePost(T_DjiSemaHandle semaphore);

T_DjiReturnCode Osal_GetTimeMs(uint32_t *ms);
T_DjiReturnCode Osal_GetTimeUs(uint64_t *us);
T_DjiReturnCode Osal_GetRandomNum(uint16_t *randomNum);

void *Osal_Malloc(uint32_t size);
void Osal_Free(void *ptr);
Expand Down

0 comments on commit 9f1e4cc

Please sign in to comment.