NEW: release DJI Payload-SDK version 3.3

Signed-off-by: DJI-Martin <DJI-Martin@dji.com>
This commit is contained in:
DJI-Martin
2022-11-18 20:59:40 +08:00
parent 513d3537e2
commit f33308c85b
79 changed files with 1185370 additions and 1979 deletions

View File

@ -15,6 +15,7 @@ set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -fprofile-arcs -ftest-cove
include_directories(../../../module_sample)
include_directories(../../../../sample_c/module_sample)
include_directories(../common)
include_directories(../manifold2/application)
file(GLOB_RECURSE MODULE_SAMPLE_SRC
../../../module_sample/liveview/*.c*
@ -67,6 +68,20 @@ if (FFMPEG_FOUND)
message(STATUS " - Includes: ${FFMPEG_INCLUDE_DIR}")
message(STATUS " - Libraries: ${FFMPEG_LIBRARIES}")
EXECUTE_PROCESS(COMMAND ffmpeg -version
OUTPUT_VARIABLE ffmpeg_version_psdk_libput
OUTPUT_STRIP_TRAILING_WHITESPACE
)
string(REGEX MATCH "version.*Copyright" ffmpeg_version_line ${ffmpeg_version_psdk_libput})
string(REGEX MATCH " .* " ffmpeg_version ${ffmpeg_version_line})
string(REGEX MATCH "^ 5.*$" ffmpeg_major_version ${ffmpeg_version})
if (HEAD${ffmpeg_major_version} STREQUAL "HEAD")
message(STATUS " - Version: ${ffmpeg_version}")
else ()
message(FATAL_ERROR " - Not support FFMPEG version: ${ffmpeg_major_version}, please install 4.x.x instead.")
endif ()
target_link_libraries(${PROJECT_NAME} ${FFMPEG_LIBRARIES})
else ()
message(STATUS "Cannot Find FFMPEG")

View File

@ -29,12 +29,14 @@
#include <dji_logger.h>
#include <dji_core.h>
#include <dji_aircraft_info.h>
#include "dji_sdk_config.h"
#include "../common/osal/osal.h"
#include "../common/osal/osal_fs.h"
#include "../common/osal/osal_socket.h"
#include "../manifold2/hal/hal_usb_bulk.h"
#include "../manifold2/hal/hal_uart.h"
#include "../manifold2/hal/hal_network.h"
/* Private constants ---------------------------------------------------------*/
#define DJI_LOG_PATH "Logs/DJI"
@ -80,6 +82,11 @@ void Application::DjiUser_SetupEnvironment()
T_DjiLoggerConsole localRecordConsole;
T_DjiFileSystemHandler fileSystemHandler;
T_DjiSocketHandler socketHandler;
T_DjiHalNetworkHandler networkHandler;
networkHandler.NetworkInit = HalNetWork_Init;
networkHandler.NetworkDeInit = HalNetWork_DeInit;
networkHandler.NetworkGetDeviceInfo = HalNetWork_GetDeviceInfo;
socketHandler.Socket = Osal_Socket;
socketHandler.Bind = Osal_Bind;
@ -153,11 +160,22 @@ void Application::DjiUser_SetupEnvironment()
throw std::runtime_error("Register hal uart handler error.");
}
#if (CONFIG_HARDWARE_CONNECTION == DJI_USE_UART_AND_USB_BULK_DEVICE)
returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Register hal usb bulk handler error.");
}
#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_UART_AND_NETWORK_DEVICE)
returnCode = DjiPlatform_RegHalNetworkHandler(&networkHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Register hal network handler error");
}
#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_UART)
/*!< Attention: Only use uart hardware connection.
*/
#endif
//Attention: if you want to use camera stream view function, please uncomment it.
returnCode = DjiPlatform_RegSocketHandler(&socketHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("register osal socket handler error");

View File

@ -0,0 +1,54 @@
/**
********************************************************************
* @file dji_sdk_config.h
* @brief This is the header file for "dji_config.c", defining the structure and
* (exported) function prototypes.
*
* @copyright (c) 2021 DJI. All rights reserved.
*
* All information contained herein is, and remains, the property of DJI.
* The intellectual and technical concepts contained herein are proprietary
* to DJI and may be covered by U.S. and foreign patents, patents in process,
* and protected by trade secret or copyright law. Dissemination of this
* information, including but not limited to data and other proprietary
* material(s) incorporated within the information, in any form, is strictly
* prohibited without the express written consent of DJI.
*
* If you receive this source code without DJIs authorization, you may not
* further disseminate the information, and you must immediately remove the
* source code and notify DJI of its removal. DJI reserves the right to pursue
* legal actions against you for any loss(es) or damage(s) caused by your
* failure to do so.
*
*********************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef DJI_SDK_CONFIG_H
#define DJI_SDK_CONFIG_H
/* Includes ------------------------------------------------------------------*/
#ifdef __cplusplus
extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
#define DJI_USE_ONLY_UART (0)
#define DJI_USE_UART_AND_USB_BULK_DEVICE (1)
#define DJI_USE_UART_AND_NETWORK_DEVICE (2)
/*!< Attention: Select your hardware connection mode here.
* */
#define CONFIG_HARDWARE_CONNECTION DJI_USE_UART_AND_NETWORK_DEVICE
/* Exported types ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
#ifdef __cplusplus
}
#endif
#endif // DJI_SDK_CONFIG_H
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/

View File

@ -74,19 +74,19 @@ start:
<< "| [6] Flight controller sample - set get parameters |\n"
<< "| [7] Hms info sample - get health manger system info |\n"
<< "| [8] Waypoint 2.0 sample - run airline mission by settings (only support on M300 RTK) |\n"
<< "| [9] Waypoint 3.0 sample - run airline mission by kmz file (only support on M30/30T) |\n"
<< "| [9] Waypoint 3.0 sample - run airline mission by kmz file (not support on M300 RTK) |\n"
<< "| [a] Gimbal manager sample - rotate gimbal on free mode |\n"
<< "| [b] Gimbal manager sample - rotate gimbal on yaw follow mode |\n"
<< "| [c] Camera stream view sample - display the camera video stream |\n"
<< "| [d] Stereo vision view sample - display the stereo image (only support on M300 RTK) |\n"
<< "| [e] Start camera all feautes sample - you can operate the camera on DJI Pilot |\n"
<< "| [f] Start gimbal all feautes sample - you can operate the gimbal on DJI Pilot |\n"
<< "| [g] Start widget all feautes sample - you can operate the widget on DJI Pilot |\n"
<< "| [h] Start widget speaker sample - you can operate the speaker on MSDK demo |\n"
<< "| [d] Stereo vision view sample - display the stereo image |\n"
<< "| [e] Start camera all features sample - you can operate the camera on DJI Pilot |\n"
<< "| [f] Start gimbal all features sample - you can operate the gimbal on DJI Pilot |\n"
<< "| [g] Start widget all features sample - you can operate the widget on DJI Pilot |\n"
<< "| [h] Start widget speaker sample - you can operate the speaker on DJI Pilot2 |\n"
<< "| [i] Start power management sample - you will see notification when aircraft power off |\n"
<< "| [j] Start data transmission sample - you can send or recv custom data on MSDK demo |\n"
<< "| [l] Run camera manager sample - shoot photo by the selected camera mounted position |\n"
<< "| [m] Run camera manager download sample - download camera media file (only support on M300 RTK) |\n"
<< "| [m] Run camera manager download sample - download camera media file (only support on M3E/M3T) |\n"
<< std::endl;
std::cin >> inputChar;
@ -140,7 +140,7 @@ start:
break;
}
if (DjiPlatform_GetSocketHandler() != NULL) {
if (DjiPlatform_GetSocketHandler() != nullptr) {
returnCode = DjiTest_CameraEmuMediaStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("camera emu media init error");

View File

@ -79,6 +79,14 @@ T_DjiReturnCode HalNetWork_DeInit(T_DjiNetworkHandle halObj)
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
T_DjiReturnCode HalNetWork_GetDeviceInfo(T_DjiHalNetworkDeviceInfo *deviceInfo)
{
deviceInfo->usbNetAdapter.vid = USB_NET_ADAPTER_VID;
deviceInfo->usbNetAdapter.pid = USB_NET_ADAPTER_PID;
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
/* Private functions definition-----------------------------------------------*/
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/

View File

@ -1,8 +1,6 @@
/**
********************************************************************
* @file hal_network.h
* @version V2.0.0
* @date 3/27/20
* @brief This is the header file for "hal_network.c", defining the structure and
* (exported) function prototypes.
*
@ -42,14 +40,21 @@ extern "C" {
* NIC name micro define as #define 'LINUX_NETWORK_DEV "your NIC name"'.
*/
#ifdef PLATFORM_ARCH_x86_64
#define LINUX_NETWORK_DEV "enp0s31f6"
#define LINUX_NETWORK_DEV "enx000ec6688213"
#else
#define LINUX_NETWORK_DEV "eth0"
#define LINUX_NETWORK_DEV "l4tbr0"
#endif
/**
* @attention
*/
#ifdef PLATFORM_ARCH_x86_64
#define USB_NET_ADAPTER_VID (0x0B95)
#define USB_NET_ADAPTER_PID (0x1790)
#else
#define USB_NET_ADAPTER_VID (0x0955)
#define USB_NET_ADAPTER_PID (0x7020)
#endif
#define LINUX_CMD_STR_MAX_SIZE (128)
@ -57,8 +62,8 @@ extern "C" {
/* Exported functions --------------------------------------------------------*/
T_DjiReturnCode HalNetWork_Init(const char *ipAddr, const char *netMask, T_DjiNetworkHandle *halObj);
T_DjiReturnCode HalNetWork_DeInit(T_DjiNetworkHandle halObj);
T_DjiReturnCode HalNetWork_GetDeviceInfo(T_DjiHalNetworkDeviceInfo *deviceInfo);
#ifdef __cplusplus
}

View File

@ -52,13 +52,9 @@ extern "C" {
/* Exported functions --------------------------------------------------------*/
T_DjiReturnCode HalUart_Init(E_DjiHalUartNum uartNum, uint32_t baudRate, T_DjiUartHandle *uartHandle);
T_DjiReturnCode HalUart_DeInit(T_DjiUartHandle uartHandle);
T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf, uint32_t len, uint32_t *realLen);
T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen);
T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *status);
#ifdef __cplusplus

View File

@ -30,11 +30,6 @@
#define LINUX_USB_BULK_TRANSFER_TIMEOUT_MS (50)
#define LINUX_USB_BULK_TRANSFER_WAIT_FOREVER (-1)
#define LINUX_USB_BULK_EP_OUT "/dev/usb-ffs/bulk/ep1"
#define LINUX_USB_BULK_EP_IN "/dev/usb-ffs/bulk/ep2"
#define LINUX_USB_PID (0x7020)
#define LINUX_USB_VID (0x0955)
/* Private types -------------------------------------------------------------*/
typedef struct {
#ifdef LIBUSB_INSTALLED
@ -44,6 +39,7 @@ typedef struct {
#endif
int32_t ep1;
int32_t ep2;
uint32_t interfaceNum;
T_DjiHalUsbBulkInfo usbBulkInfo;
} T_HalUsbBulkObj;
@ -87,15 +83,28 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan
} else {
((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle;
memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo));
((T_HalUsbBulkObj *) *usbBulkHandle)->interfaceNum = usbBulkInfo.channelInfo.interfaceNum;
((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK_EP_OUT, O_RDWR);
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK1_INTERFACE_NUM) {
((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK1_EP_OUT_FD, O_RDWR);
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK_EP_IN, O_RDWR);
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK1_EP_IN_FD, O_RDWR);
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
} else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK2_INTERFACE_NUM) {
((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK2_EP_OUT_FD, O_RDWR);
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK2_EP_IN_FD, O_RDWR);
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
}
}
@ -197,6 +206,16 @@ T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo)
deviceInfo->vid = LINUX_USB_VID;
deviceInfo->pid = LINUX_USB_PID;
// This bulk channel is used to obtain DJI camera video stream and push 3rd-party camera video stream.
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].interfaceNum = LINUX_USB_BULK1_INTERFACE_NUM;
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].endPointIn = LINUX_USB_BULK1_END_POINT_IN;
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].endPointOut = LINUX_USB_BULK1_END_POINT_OUT;
// This bulk channel is used to obtain DJI perception image and download camera media file.
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].interfaceNum = LINUX_USB_BULK2_INTERFACE_NUM;
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointIn = LINUX_USB_BULK2_END_POINT_IN;
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointOut = LINUX_USB_BULK2_END_POINT_OUT;
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}

View File

@ -38,32 +38,49 @@
#include <sys/socket.h>
#include <netinet/in.h>
#include <arpa/inet.h>
#include "dji_platform.h"
#ifdef LIBUSB_INSTALLED
#include <libusb-1.0/libusb.h>
#endif
#include "dji_platform.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
#define LINUX_USB_BULK1_EP_OUT_FD "/dev/usb-ffs/bulk1/ep1"
#define LINUX_USB_BULK1_EP_IN_FD "/dev/usb-ffs/bulk1/ep2"
#define LINUX_USB_BULK1_INTERFACE_NUM (2)
#define LINUX_USB_BULK1_END_POINT_IN (0x83)
#define LINUX_USB_BULK1_END_POINT_OUT (2)
#define LINUX_USB_BULK2_EP_OUT_FD "/dev/usb-ffs/bulk2/ep1"
#define LINUX_USB_BULK2_EP_IN_FD "/dev/usb-ffs/bulk2/ep2"
#define LINUX_USB_BULK2_INTERFACE_NUM (3)
#define LINUX_USB_BULK2_END_POINT_IN (0x84)
#define LINUX_USB_BULK2_END_POINT_OUT (3)
#ifdef PLATFORM_ARCH_x86_64
#define LINUX_USB_VID (0x0B95)
#define LINUX_USB_PID (0x1790)
#else
#define LINUX_USB_VID (0x0955)
#define LINUX_USB_PID (0x7020)
#endif
/* Exported types ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHandle *usbBulkHandle);
T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle);
T_DjiReturnCode HalUsbBulk_WriteData(T_DjiUsbBulkHandle usbBulkHandle, const uint8_t *buf, uint32_t len,
uint32_t *realLen);
T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len, uint32_t *realLen);
T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle);
T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo);
#ifdef __cplusplus