NEW: release DJI Payload-SDK version 3.4

Signed-off-by: DJI-Martin <DJI-Martin@dji.com>
This commit is contained in:
DJI-Martin
2023-04-18 21:26:50 +08:00
parent b621c93fde
commit 29109dd0db
106 changed files with 3030521 additions and 1114 deletions

View File

@ -0,0 +1,163 @@
/**
********************************************************************
* @file test_camera_manager_entry.cpp
* @brief
*
* @copyright (c) 2018 DJI. All rights reserved.
*
* All information contained herein is, and remains, the property of DJI.
* The intellectual and technical concepts contained herein are proprietary
* to DJI and may be covered by U.S. and foreign patents, patents in process,
* and protected by trade secret or copyright law. Dissemination of this
* information, including but not limited to data and other proprietary
* material(s) incorporated within the information, in any form, is strictly
* prohibited without the express written consent of DJI.
*
* If you receive this source code without DJIs authorization, you may not
* further disseminate the information, and you must immediately remove the
* source code and notify DJI of its removal. DJI reserves the right to pursue
* legal actions against you for any loss(es) or damage(s) caused by your
* failure to do so.
*
*********************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include <iostream>
#include <string>
#include <dji_logger.h>
#include <dji_typedef.h>
#include "utils/util_misc.h"
#include "dji_camera_manager.h"
#include "camera_manager/test_camera_manager.h"
#include "camera_manager/test_camera_manager_entry.h"
#include "test_camera_manager_entry.h"
using namespace std;
/* Private constants ---------------------------------------------------------*/
static const char *s_cameraManagerSampleSelectList[] = {
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_SHUTTER_SPEED] = "Set camera shutter speed |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_APERTURE] = "Set camera aperture |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_EV] = "Set camera ev |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_ISO] = "Set camera iso |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_FOCUS_POINT] = "Set camera focus point |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_TAP_ZOOM_POINT] = "Set camera tap zoom point |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_ZOOM_PARAM] = "Set camera zoom param |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_SINGLE_PHOTO] = "Shoot single photo |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_AEB_PHOTO] = "Shoot aeb photo |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_BURST_PHOTO] = "Shoot busrt photo |",
[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_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 |",
};
/* Private types -------------------------------------------------------------*/
/* Private values -------------------------------------------------------------*/
/* Private functions declaration ---------------------------------------------*/
static void DjiTest_CmareManagerShowStringList(const char **list, int size)
{
for (int i = 0; i < size; i++) {
printf("| [%2d] %s\r\n", i, list[i]);
}
}
static void DjiTest_CameraManagerShowSampleSelectList(void)
{
DjiTest_CmareManagerShowStringList(s_cameraManagerSampleSelectList,
UTIL_ARRAY_SIZE(s_cameraManagerSampleSelectList));
}
/* Exported functions definition ---------------------------------------------*/
void DjiUser_RunCameraManagerSample(void)
{
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
string mountPositionStr;
int posNum;
E_DjiMountPosition cameraMountPosition;
string sampleSelectStr;
int sampleSelectNum;
E_DjiTestCameraManagerSampleSelect cameraSample;
USER_LOG_INFO("DjiUser_RunCameraManagerSample");
while (true) {
osalHandler->TaskSleepMs(10);
cout
<< "| Available position: |"
<<
endl;
cout
<< "| [1] Select gimbal mount position at NO.1 payload port |"
<<
endl;
cout
<< "| [2] Select gimbal mount position at NO.2 payload port |"
<<
endl;
cout
<< "| [3] Select gimbal mount position at NO.3 payload port |"
<<
endl;
cout
<< "| [q] Quit |"
<<
endl;
cout << "Please input number to select position (input q to quit): ";
cin >> mountPositionStr;
if (mountPositionStr == "q") {
return;
}
posNum = atoi(mountPositionStr.c_str());
if (posNum > 3 || posNum < 1) {
USER_LOG_ERROR("Input mount position is invalid");
continue;
}
else {
break;
}
}
cameraMountPosition = E_DjiMountPosition(posNum);
while (true) {
osalHandler->TaskSleepMs(10);
cout << "\nAvailable samples:\n";
DjiTest_CameraManagerShowSampleSelectList();
cout << "Please input number to select sample (input q to quit): ";
cin >> sampleSelectStr;
if (sampleSelectStr == "q") {
return;
}
sampleSelectNum = atoi(sampleSelectStr.c_str());
if (sampleSelectNum < 0 ||
sampleSelectNum >= (int)E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_INDEX_MAX) {
USER_LOG_ERROR("Input camera sample is invalid");
continue;
}
cameraSample = (E_DjiTestCameraManagerSampleSelect)sampleSelectNum;
cout << "Start test: position " << cameraMountPosition
<< ", sample " << cameraSample << endl;
DjiTest_CameraManagerRunSample(cameraMountPosition, cameraSample);
}
}
/* Private functions definition-----------------------------------------------*/
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/

View File

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

View File

@ -0,0 +1,129 @@
/**
********************************************************************
* @file test_gimbal_entry.cpp
* @version V2.0.0
* @date 2023/3/28
* @brief
*
* @copyright (c) 2018-2023 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.
*
*********************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include <stdexcept>
#include "test_gimbal_entry.hpp"
#include "dji_logger.h"
#include "utils/util_misc.h"
#include <iostream>
/* Private constants ---------------------------------------------------------*/
/* Private types -------------------------------------------------------------*/
typedef enum {
E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_ROTATE_GIMBAL_ON_FREE_MODE,
E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_ROTATE_GIMBAL_ON_YAW_FOLLOW_MODE,
E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_QUIT,
} E_DjiTestGimbalManagerSampleSelect;
/* Private values -------------------------------------------------------------*/
static const char *s_gimbalManagerSampleList[] = {
[E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_ROTATE_GIMBAL_ON_FREE_MODE] =
"| [0] Gimbal manager sample - Rotate gimbal on free mode |",
[E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_ROTATE_GIMBAL_ON_YAW_FOLLOW_MODE] =
"| [1] Gimbal manager sample - Rotate gimbal on yaw follow mode |",
[E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_QUIT] =
"| [q] Gimbal manager sample - Quit |",
};
/* Private functions declaration ---------------------------------------------*/
void DjiTest_GimbalManagerShowSampleSelectList(const char **SampleList, uint8_t size);
/* Exported functions definition ---------------------------------------------*/
void DjiUser_RunGimbalManagerSample(void)
{
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
char inputTestCase;
char mountPosition;
E_DjiMountPosition gimbalMountPosition;
start:
osalHandler->TaskSleepMs(100);
std::cout
<< "| Available position: |"
<<
std::endl;
std::cout
<< "| [1] Select gimbal mount position at NO.1 payload port |"
<<
std::endl;
std::cout
<< "| [2] Select gimbal mount position at NO.2 payload port |"
<<
std::endl;
std::cout
<< "| [3] Select gimbal mount position at NO.3 payload port |"
<<
std::endl;
std::cout
<< "| [q] Quit |"
<<
std::endl;
std::cin >> mountPosition;
if (mountPosition == 'q') {
return;
}
if (mountPosition > '3' || mountPosition < '1') {
USER_LOG_ERROR("Input mount position is invalid");
goto start;
}
gimbalMountPosition = E_DjiMountPosition(mountPosition - '0');
osalHandler->TaskSleepMs(100);
std::cout
<< "| Available commands: |"
<<
std::endl;
DjiTest_GimbalManagerShowSampleSelectList(s_gimbalManagerSampleList, UTIL_ARRAY_SIZE(s_gimbalManagerSampleList));
std::cin >> inputTestCase;
switch (inputTestCase) {
case '0':
DjiTest_GimbalManagerRunSample(gimbalMountPosition, DJI_GIMBAL_MODE_FREE);
goto start;
case '1':
DjiTest_GimbalManagerRunSample(gimbalMountPosition, DJI_GIMBAL_MODE_YAW_FOLLOW);
goto start;
case 'q':
break;
default:
USER_LOG_ERROR("Input command is invalid");
goto start;
}
return;
}
/* Private functions definition-----------------------------------------------*/
void DjiTest_GimbalManagerShowSampleSelectList(const char **SampleList, uint8_t size) {
uint8_t i = 0;
for (i = 0; i < size; i++) {
std::cout << SampleList[i] << std::endl;
}
}
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/

View File

@ -0,0 +1,51 @@
/**
********************************************************************
* @file test_gimbal_entry.hpp
* @version V2.0.0
* @date 2023/3/28
* @brief This is the header file for "test_gimbal_entry.cpp", defining the structure and
* (exported) function prototypes.
*
* @copyright (c) 2018-2023 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 TEST_GIMBAL_ENTRY_H
#define TEST_GIMBAL_ENTRY_H
/* Includes ------------------------------------------------------------------*/
#include <gimbal_manager/test_gimbal_manager.h>
#ifdef __cplusplus
extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
void DjiUser_RunGimbalManagerSample(void);
#ifdef __cplusplus
}
#endif
#endif // TEST_GIMBAL_ENTRY_H
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/

View File

@ -43,6 +43,7 @@ DJICameraStreamDecoder::DJICameraStreamDecoder()
cbThreadStatus(-1),
cb(nullptr),
cbUserParam(nullptr),
#ifdef FFMPEG_INSTALLED
pCodecCtx(nullptr),
pCodec(nullptr),
pCodecParserCtx(nullptr),
@ -50,6 +51,7 @@ DJICameraStreamDecoder::DJICameraStreamDecoder()
pFrameYUV(nullptr),
pFrameRGB(nullptr),
rgbBuf(nullptr),
#endif
bufSize(0)
{
pthread_mutex_init(&decodemutex, nullptr);
@ -75,6 +77,7 @@ bool DJICameraStreamDecoder::init()
return true;
}
#ifdef FFMPEG_INSTALLED
avcodec_register_all();
pCodecCtx = avcodec_alloc_context3(nullptr);
if (!pCodecCtx) {
@ -105,8 +108,8 @@ bool DJICameraStreamDecoder::init()
pSwsCtx = nullptr;
pCodecCtx->flags2 |= AV_CODEC_FLAG2_SHOW_ALL;
#endif
initSuccess = true;
pthread_mutex_unlock(&decodemutex);
return true;
@ -117,6 +120,8 @@ void DJICameraStreamDecoder::cleanup()
pthread_mutex_lock(&decodemutex);
initSuccess = false;
#ifdef FFMPEG_INSTALLED
if (nullptr != pSwsCtx) {
sws_freeContext(pSwsCtx);
pSwsCtx = nullptr;
@ -151,7 +156,7 @@ void DJICameraStreamDecoder::cleanup()
av_free(pFrameRGB);
pFrameRGB = nullptr;
}
#endif
pthread_mutex_unlock(&decodemutex);
}
@ -184,6 +189,7 @@ void DJICameraStreamDecoder::decodeBuffer(const uint8_t *buf, int bufLen)
int remainingLen = bufLen;
int processedLen = 0;
#ifdef FFMPEG_INSTALLED
AVPacket pkt;
av_init_packet(&pkt);
pthread_mutex_lock(&decodemutex);
@ -238,6 +244,7 @@ void DJICameraStreamDecoder::decodeBuffer(const uint8_t *buf, int bufLen)
}
pthread_mutex_unlock(&decodemutex);
av_free_packet(&pkt);
#endif
}
bool DJICameraStreamDecoder::registerCallback(CameraImageCallback f, void *param)

View File

@ -29,9 +29,11 @@
/* Includes ------------------------------------------------------------------*/
extern "C" {
#ifdef FFMPEG_INSTALLED
#include <libavcodec/avcodec.h>
#include <libavformat/avformat.h>
#include <libswscale/swscale.h>
#endif
}
#include "pthread.h"
@ -66,6 +68,8 @@ private:
void *cbUserParam;
pthread_mutex_t decodemutex;
#ifdef FFMPEG_INSTALLED
AVCodecContext *pCodecCtx;
AVCodec *pCodec;
AVCodecParserContext *pCodecParserCtx;
@ -73,6 +77,7 @@ private:
AVFrame *pFrameYUV;
AVFrame *pFrameRGB;
#endif
uint8_t *rgbBuf;
size_t bufSize;
};

View File

@ -42,7 +42,7 @@ LiveviewSample::LiveviewSample()
returnCode = DjiLiveview_Init();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Liveview init failed");
perror("Liveview init failed");
}
streamDecoder = {
@ -59,7 +59,7 @@ LiveviewSample::~LiveviewSample()
returnCode = DjiLiveview_Deinit();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Liveview deinit failed");
perror("Liveview deinit failed");
}
for (auto pair : streamDecoder) {

View File

@ -204,9 +204,17 @@ static void DjiUser_ShowRgbImageCallback(CameraRGBImage img, void *userData)
cout << " x: " << faces[i].x;
cout << " y: " << faces[i].y << endl;
#ifdef OPEN_CV_VERSION_3
cv::rectangle(mat, cvPoint(faces[i].x, faces[i].y),
cvPoint(faces[i].x + faces[i].width, faces[i].y + faces[i].height),
Scalar(0, 0, 255), 2, 1, 0);
#endif
#ifdef OPEN_CV_VERSION_4
cv::rectangle(mat, cv::Point(faces[i].x, faces[i].y),
cv::Point(faces[i].x + faces[i].width, faces[i].y + faces[i].height),
Scalar(0, 0, 255), 2, 1, 0);
#endif
}
imshow(name, mat);
} else if (s_demoIndex == 3) {
@ -265,8 +273,15 @@ static void DjiUser_ShowRgbImageCallback(CameraRGBImage img, void *userData)
int baseLine = 0;
Size labelSize = getTextSize(label, FONT_HERSHEY_SIMPLEX, 0.5, 1, &baseLine);
#ifdef OPEN_CV_VERSION_3
rectangle(mat, Rect(Point(xLeftBottom, yLeftBottom - labelSize.height),
Size(labelSize.width, labelSize.height + baseLine)), Scalar(0, 255, 0), CV_FILLED);
#endif
#ifdef OPEN_CV_VERSION_4
rectangle(mat, Rect(Point(xLeftBottom, yLeftBottom - labelSize.height),
Size(labelSize.width, labelSize.height + baseLine)), Scalar(0, 255, 0), cv::FILLED);
#endif
putText(mat, label, Point(xLeftBottom, yLeftBottom), FONT_HERSHEY_SIMPLEX, 0.5, Scalar(0, 0, 0));
}
}

View File

@ -42,12 +42,11 @@ PerceptionSample::PerceptionSample()
returnCode = DjiPerception_Init();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
if (returnCode == DJI_ERROR_SYSTEM_MODULE_CODE_NONSUPPORT) {
USER_LOG_ERROR("Perception feature will support on later version.");
}
throw std::runtime_error("Perception init failed");
perror("Perception init failed");
}
}
@ -57,7 +56,7 @@ PerceptionSample::~PerceptionSample()
returnCode = DjiPerception_Deinit();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Perception deinit failed");
perror("Perception deinit failed");
}
}

View File

@ -39,6 +39,8 @@
/* Private constants ---------------------------------------------------------*/
#define USER_PERCEPTION_TASK_STACK_SIZE (1024)
#define USER_PERCEPTION_DIRECTION_NUM (12)
#define FPS_STRING_LEN (50)
/* Private types -------------------------------------------------------------*/
typedef struct {
@ -320,6 +322,14 @@ static void *DjiTest_StereoImagesDisplayTask(void *arg)
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
auto *pack = (T_DjiTestStereoImagePacket *) arg;
char nameStr[32] = {0};
char fpsStr[20] = "FPS: ";
int fps = 0;
double timePrev[USER_PERCEPTION_DIRECTION_NUM] = {0};
double timeNow[USER_PERCEPTION_DIRECTION_NUM] = {0};
double timeFess[USER_PERCEPTION_DIRECTION_NUM] = {0};
int count[USER_PERCEPTION_DIRECTION_NUM] = {1};
char showFpsString[USER_PERCEPTION_DIRECTION_NUM][FPS_STRING_LEN] = {0};
int i = 0;
while (true) {
osalHandler->TaskSleepMs(1);
@ -338,7 +348,7 @@ static void *DjiTest_StereoImagesDisplayTask(void *arg)
pack->imageRawBuffer = NULL;
}
for (int i = 0; i < sizeof(positionName) / sizeof(T_DjiTestPerceptionCameraPositionName); ++i) {
for (i = 0; i < sizeof(positionName) / sizeof(T_DjiTestPerceptionCameraPositionName); ++i) {
if (positionName[i].cameraPosition == pack->info.dataType) {
sprintf(nameStr, "Image position: %s", positionName[i].name);
break;
@ -355,6 +365,31 @@ static void *DjiTest_StereoImagesDisplayTask(void *arg)
cv::moveWindow(nameStr, (200 + (int) pack->info.rawInfo.width), 0);
}
if (i < USER_PERCEPTION_DIRECTION_NUM) {
/*! Calculate frame rate */
timeNow[i] = (double) cv::getTickCount();
if (timePrev[i] != 0) {
timeFess[i] = (timeNow[i] - timePrev[i]) / cv::getTickFrequency() + timeFess[i];
count[i]++;
}
if (timeFess[i] > 1) {
memset(&showFpsString[i][0], 0, FPS_STRING_LEN);
fps = count[i] / timeFess[i];
timeFess[i] = 0;
count[i] = 0;
sprintf(&showFpsString[i][0], "%s%d", fpsStr, fps);
}
timePrev[i] = timeNow[i];
#ifdef OPEN_CV_VERSION_3
cv::putText(cv_img_stereo, &showFpsString[i][0], cv::Point(5, 20),
CV_FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(0, 0, 0));
#endif
#ifdef OPEN_CV_VERSION_4
cv::putText(cv_img_stereo, &showFpsString[i][0], cv::Point(5, 20),
cv::FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(0, 0, 0));
#endif
}
cv::imshow(nameStr, cv_img_stereo);
cv::waitKey(1);
#else

View File

@ -42,15 +42,10 @@
/* Exported functions definition ---------------------------------------------*/
T_DjiReturnCode Osal_FileOpen(const char *fileName, const char *fileMode, T_DjiFileHandle *fileObj)
{
if (fileName == NULL || fileMode == NULL) {
if (fileName == NULL || fileMode == NULL || fileObj == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}
*fileObj = malloc(sizeof(FILE));
if (*fileObj == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_MEMORY_ALLOC_FAILED;
}
*fileObj = fopen(fileName, fileMode);
if (*fileObj == NULL) {
goto out;

View File

@ -31,12 +31,13 @@
#include "stdlib.h"
/* Private constants ---------------------------------------------------------*/
#define SOCKET_RECV_BUF_MAX_SIZE (1000 * 1000 * 10)
/* Private types -------------------------------------------------------------*/
typedef struct {
int socketFd;
} T_SocketHandleStruct;
/* Private types -------------------------------------------------------------*/
/* Private values -------------------------------------------------------------*/
/* Private functions declaration ---------------------------------------------*/
@ -45,6 +46,15 @@ typedef struct {
T_DjiReturnCode Osal_Socket(E_DjiSocketMode mode, T_DjiSocketHandle *socketHandle)
{
T_SocketHandleStruct *socketHandleStruct;
socklen_t optlen = sizeof(int);
int rcvBufSize = SOCKET_RECV_BUF_MAX_SIZE;
int opt = 1;
/*! set the socket default read buffer to 20MByte */
system("echo 20000000 > /proc/sys/net/core/rmem_default");
/*! set the socket max read buffer to 50MByte */
system("echo 50000000 > /proc/sys/net/core/rmem_max");
if (socketHandle == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
@ -57,15 +67,30 @@ T_DjiReturnCode Osal_Socket(E_DjiSocketMode mode, T_DjiSocketHandle *socketHandl
if (mode == DJI_SOCKET_MODE_UDP) {
socketHandleStruct->socketFd = socket(PF_INET, SOCK_DGRAM, 0);
if (setsockopt(socketHandleStruct->socketFd, SOL_SOCKET, SO_REUSEADDR, &opt, optlen) < 0) {
goto out;
}
if (setsockopt(socketHandleStruct->socketFd, SOL_SOCKET, SO_RCVBUF, &rcvBufSize, optlen) < 0) {
goto out;
}
} else if (mode == DJI_SOCKET_MODE_TCP) {
socketHandleStruct->socketFd = socket(PF_INET, SOCK_STREAM, 0);
} else {
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
goto out;
}
*socketHandle = socketHandleStruct;
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
out:
close(socketHandleStruct->socketFd);
free(socketHandleStruct);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
T_DjiReturnCode Osal_Close(T_DjiSocketHandle socketHandle)
@ -82,6 +107,8 @@ T_DjiReturnCode Osal_Close(T_DjiSocketHandle socketHandle)
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
free(socketHandle);
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}

View File

@ -19,7 +19,9 @@ include_directories(../manifold2/application)
file(GLOB_RECURSE MODULE_SAMPLE_SRC
../../../module_sample/liveview/*.c*
../../../module_sample/camera_manager/*.c*
../../../module_sample/perception/*.c*
../../../module_sample/gimbal/*.c*
../../../../sample_c/module_sample/*.c
)
file(GLOB_RECURSE MODULE_COMMON_SRC ../common/*.c*)
@ -49,7 +51,7 @@ add_executable(${PROJECT_NAME}
${MODULE_COMMON_SRC}
${MODULE_HAL_SRC})
# Try to see if user has OpenCV installed因为额
# Try to see if user has OpenCV installed
# if yes, default callback will display the image
find_package(OpenCV QUIET)
if (OpenCV_FOUND)
@ -58,6 +60,12 @@ if (OpenCV_FOUND)
message(STATUS " - Includes: ${OpenCV_INCLUDE_DIRS}")
message(STATUS " - Libraries: ${OpenCV_LIBRARIES}")
add_definitions(-DOPEN_CV_INSTALLED)
execute_process(COMMAND opencv_version OUTPUT_VARIABLE OPENCV_VERSION)
if (${OPENCV_VERSION} STRLESS "4.0.0")
add_definitions(-DOPEN_CV_VERSION_3)
else()
add_definitions(-DOPEN_CV_VERSION_4)
endif()
else ()
message(STATUS "Did not find OpenCV in the system, image data is inside RecvContainer as raw data")
endif ()
@ -83,10 +91,11 @@ if (FFMPEG_FOUND)
endif ()
target_link_libraries(${PROJECT_NAME} ${FFMPEG_LIBRARIES})
include_directories(${FFMPEG_INCLUDE_DIR})
add_definitions(-DFFMPEG_INSTALLED)
else ()
message(STATUS "Cannot Find FFMPEG")
endif (FFMPEG_FOUND)
include_directories(${FFMPEG_INCLUDE_DIR})
include_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/include)
find_package(OPUS REQUIRED)

View File

@ -29,6 +29,7 @@
#include <dji_logger.h>
#include <dji_core.h>
#include <dji_aircraft_info.h>
#include <csignal>
#include "dji_sdk_config.h"
#include "../common/osal/osal.h"
@ -58,6 +59,7 @@ static FILE *s_djiLogFile;
static FILE *s_djiLogFileCnt;
/* Private functions declaration ---------------------------------------------*/
static void DjiUser_NormalExitHandler(int signalNum);
/* Exported functions definition ---------------------------------------------*/
Application::Application(int argc, char **argv)
@ -206,6 +208,15 @@ void Application::DjiUser_ApplicationStart()
T_DjiUserInfo userInfo;
T_DjiReturnCode returnCode;
T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo;
T_DjiFirmwareVersion firmwareVersion = {
.majorVersion = 1,
.minorVersion = 0,
.modifyVersion = 0,
.debugVersion = 0,
};
// attention: when the program is hand up ctrl-c will generate the coredump file
signal(SIGTERM, DjiUser_NormalExitHandler);
returnCode = DjiUser_FillInUserInfo(&userInfo);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
@ -231,6 +242,16 @@ void Application::DjiUser_ApplicationStart()
throw std::runtime_error("Set alias error.");
}
returnCode = DjiCore_SetFirmwareVersion(firmwareVersion);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Set firmware version error.");
}
returnCode = DjiCore_SetSerialNumber("PSDK12345678XX");
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Set serial number error");
}
returnCode = DjiCore_ApplicationStart();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Start sdk application error.");
@ -389,4 +410,10 @@ T_DjiReturnCode Application::DjiUser_LocalWriteFsInit(const char *path)
return djiReturnCode;
}
static void DjiUser_NormalExitHandler(int signalNum)
{
USER_UTIL_UNUSED(signalNum);
exit(0);
}
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/

View File

@ -26,6 +26,7 @@
#include <liveview/test_liveview_entry.hpp>
#include <perception/test_perception_entry.hpp>
#include <flight_control/test_flight_control.h>
#include <gimbal/test_gimbal_entry.hpp>
#include <hms/test_hms.h>
#include <waypoint_v2/test_waypoint_v2.h>
#include <waypoint_v3/test_waypoint_v3.h>
@ -41,6 +42,7 @@
#include <power_management/test_power_management.h>
#include "data_transmission/test_data_transmission.h"
#include <camera_manager/test_camera_manager.h>
#include "camera_manager/test_camera_manager_entry.h"
/* Private constants ---------------------------------------------------------*/
@ -75,8 +77,7 @@ start:
<< "| [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 (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"
<< "| [a] Gimbal manager sample |\n"
<< "| [c] Camera stream view sample - display the camera video stream |\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"
@ -85,8 +86,7 @@ start:
<< "| [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 (not support on M3E/M3T) |\n"
<< "| [k] Run camera manager sample - you can test camera's functions interactively |\n"
<< std::endl;
std::cin >> inputChar;
@ -122,10 +122,7 @@ start:
DjiTest_WaypointV3RunSample();
break;
case 'a':
DjiTest_GimbalManagerRunSample(DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1, DJI_GIMBAL_MODE_FREE);
break;
case 'b':
DjiTest_GimbalManagerRunSample(DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1, DJI_GIMBAL_MODE_YAW_FOLLOW);
DjiUser_RunGimbalManagerSample();
break;
case 'c':
DjiUser_RunCameraStreamViewSample();
@ -203,14 +200,8 @@ start:
USER_LOG_INFO("Start data transmission sample successfully");
break;
case 'l':
DjiTest_CameraManagerRunSample(DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_SINGLE_PHOTO);
break;
case 'm':
DjiTest_CameraManagerRunSample(DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_DOWNLOAD_AND_DELETE_MEDIA_FILE);
exit(1);
case 'k':
DjiUser_RunCameraManagerSample();
break;
default:
break;

View File

@ -40,7 +40,7 @@ extern "C" {
* NIC name micro define as #define 'LINUX_NETWORK_DEV "your NIC name"'.
*/
#ifdef PLATFORM_ARCH_x86_64
#define LINUX_NETWORK_DEV "enx000ec6688213"
#define LINUX_NETWORK_DEV "enxf8e43b7bbc2c"
#else
#define LINUX_NETWORK_DEV "l4tbr0"
#endif

View File

@ -38,6 +38,7 @@
#include <sys/socket.h>
#include <netinet/in.h>
#include <arpa/inet.h>
#ifdef LIBUSB_INSTALLED
#include <libusb-1.0/libusb.h>

View File

@ -0,0 +1,134 @@
cmake_minimum_required(VERSION 3.5)
project(dji_sdk_demo_on_jeston_cxx CXX)
set(CMAKE_C_FLAGS "-pthread -std=gnu99")
set(CMAKE_EXE_LINKER_FLAGS "-pthread")
set(CMAKE_C_COMPILER "aarch64-linux-gnu-gcc")
set(CMAKE_CXX_COMPILER "aarch64-linux-gnu-g++")
add_definitions(-D_GNU_SOURCE)
if (BUILD_TEST_CASES_ON MATCHES TRUE)
set(COMMON_CXX_FLAGS "-std=c++11 -pthread")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${COMMON_CXX_FLAGS} -fprofile-arcs -ftest-coverage -Wno-deprecated-declarations")
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fprofile-arcs -ftest-coverage")
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -fprofile-arcs -ftest-coverage -lgcov")
endif ()
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*
../../../module_sample/camera_manager/*.c*
../../../module_sample/perception/*.c*
../../../module_sample/gimbal/*.c*
../../../../sample_c/module_sample/*.c
)
file(GLOB_RECURSE MODULE_COMMON_SRC ../common/*.c*)
file(GLOB_RECURSE MODULE_HAL_SRC hal/*.c*)
file(GLOB_RECURSE MODULE_APP_SRC application/*.c*)
set(TOOLCHAIN_NAME aarch64-linux-gnu-gcc)
add_definitions(-DPLATFORM_ARCH_aarch64=1)
add_definitions(-DSYSTEM_ARCH_LINUX=1)
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/../common/3rdparty)
link_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../out/lib/${TOOLCHAIN_NAME})
link_libraries(${CMAKE_CURRENT_LIST_DIR}/../../../../../out/lib/${TOOLCHAIN_NAME}/libpayloadsdk.a -lstdc++)
add_executable(${PROJECT_NAME}
${MODULE_APP_SRC}
${MODULE_SAMPLE_SRC}
${MODULE_COMMON_SRC}
${MODULE_HAL_SRC})
# Try to see if user has OpenCV installed
# if yes, default callback will display the image
find_package(OpenCV QUIET)
if (OpenCV_FOUND)
message("\n${PROJECT_NAME}...")
message(STATUS "Found OpenCV installed in the system, will use it to display image in AdvancedSensing APIs")
message(STATUS " - Includes: ${OpenCV_INCLUDE_DIRS}")
message(STATUS " - Libraries: ${OpenCV_LIBRARIES}")
add_definitions(-DOPEN_CV_INSTALLED)
execute_process(COMMAND opencv_version OUTPUT_VARIABLE OPENCV_VERSION)
if (${OPENCV_VERSION} STRLESS "4.0.0")
add_definitions(-DOPEN_CV_VERSION_3)
else()
add_definitions(-DOPEN_CV_VERSION_4)
endif()
else ()
message(STATUS "Did not find OpenCV in the system, image data is inside RecvContainer as raw data")
endif ()
find_package(FFMPEG REQUIRED)
if (FFMPEG_FOUND)
message(STATUS "Found FFMPEG installed in the system")
message(STATUS " - Includes: ${FFMPEG_INCLUDE_DIR}")
message(STATUS " - Libraries: ${FFMPEG_LIBRARIES}")
add_definitions(-DFFMPEG_INSTALLED)
EXECUTE_PROCESS(COMMAND ffmpeg -version
OUTPUT_VARIABLE ffmpeg_version_output
OUTPUT_STRIP_TRAILING_WHITESPACE
)
string(REGEX MATCH "version.*Copyright" ffmpeg_version_line ${ffmpeg_version_output})
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")
endif (FFMPEG_FOUND)
include_directories(${FFMPEG_INCLUDE_DIR})
include_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../out/include)
find_package(OPUS REQUIRED)
if (OPUS_FOUND)
message(STATUS "Found OPUS installed in the system")
message(STATUS " - Includes: ${OPUS_INCLUDE_DIR}")
message(STATUS " - Libraries: ${OPUS_LIBRARY}")
add_definitions(-DOPUS_INSTALLED)
target_link_libraries(${PROJECT_NAME} /usr/local/lib/libopus.a)
else ()
message(STATUS "Cannot Find OPUS")
endif (OPUS_FOUND)
find_package(LIBUSB REQUIRED)
if (LIBUSB_FOUND)
message(STATUS "Found LIBUSB installed in the system")
message(STATUS " - Includes: ${LIBUSB_INCLUDE_DIR}")
message(STATUS " - Libraries: ${LIBUSB_LIBRARY}")
add_definitions(-DLIBUSB_INSTALLED)
target_link_libraries(${PROJECT_NAME} usb-1.0)
else ()
message(STATUS "Cannot Find LIBUSB")
endif (LIBUSB_FOUND)
if (NOT EXECUTABLE_OUTPUT_PATH)
set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
endif ()
target_link_libraries(${PROJECT_NAME} m)
add_custom_command(TARGET ${PROJECT_NAME}
PRE_LINK COMMAND cmake ..
WORKING_DIRECTORY ${CMAKE_BINARY_DIR})
target_include_directories(${PROJECT_NAME} PRIVATE ${OpenCV_INCLUDE_DIRS})
if (OpenCV_FOUND)
target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS})
endif ()

View File

@ -0,0 +1,419 @@
/**
********************************************************************
* @file application.cpp
* @brief
*
* @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.
*
*********************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "application.hpp"
#include "dji_sdk_app_info.h"
#include <dji_platform.h>
#include <dji_logger.h>
#include <dji_core.h>
#include <dji_aircraft_info.h>
#include <csignal>
#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"
#define DJI_LOG_INDEX_FILE_NAME "Logs/latest"
#define DJI_LOG_FOLDER_NAME "Logs"
#define DJI_LOG_PATH_MAX_SIZE (128)
#define DJI_LOG_FOLDER_NAME_MAX_SIZE (32)
#define DJI_SYSTEM_CMD_STR_MAX_SIZE (64)
#define DJI_LOG_MAX_COUNT (10)
#define USER_UTIL_UNUSED(x) ((x) = (x))
#define USER_UTIL_MIN(a, b) (((a) < (b)) ? (a) : (b))
#define USER_UTIL_MAX(a, b) (((a) > (b)) ? (a) : (b))
/* Private types -------------------------------------------------------------*/
/* Private values -------------------------------------------------------------*/
static FILE *s_djiLogFile;
static FILE *s_djiLogFileCnt;
/* Private functions declaration ---------------------------------------------*/
static void DjiUser_NormalExitHandler(int signalNum);
/* Exported functions definition ---------------------------------------------*/
Application::Application(int argc, char **argv)
{
Application::DjiUser_SetupEnvironment();
Application::DjiUser_ApplicationStart();
Osal_TaskSleepMs(3000);
}
Application::~Application()
= default;
/* Private functions definition-----------------------------------------------*/
void Application::DjiUser_SetupEnvironment()
{
T_DjiReturnCode returnCode;
T_DjiOsalHandler osalHandler;
T_DjiHalUartHandler uartHandler;
T_DjiHalUsbBulkHandler usbBulkHandler;
T_DjiLoggerConsole printConsole;
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;
socketHandler.Close = Osal_Close;
socketHandler.UdpSendData = Osal_UdpSendData;
socketHandler.UdpRecvData = Osal_UdpRecvData;
socketHandler.TcpListen = Osal_TcpListen;
socketHandler.TcpAccept = Osal_TcpAccept;
socketHandler.TcpConnect = Osal_TcpConnect;
socketHandler.TcpSendData = Osal_TcpSendData;
socketHandler.TcpRecvData = Osal_TcpRecvData;
osalHandler.TaskCreate = Osal_TaskCreate;
osalHandler.TaskDestroy = Osal_TaskDestroy;
osalHandler.TaskSleepMs = Osal_TaskSleepMs;
osalHandler.MutexCreate = Osal_MutexCreate;
osalHandler.MutexDestroy = Osal_MutexDestroy;
osalHandler.MutexLock = Osal_MutexLock;
osalHandler.MutexUnlock = Osal_MutexUnlock;
osalHandler.SemaphoreCreate = Osal_SemaphoreCreate;
osalHandler.SemaphoreDestroy = Osal_SemaphoreDestroy;
osalHandler.SemaphoreWait = Osal_SemaphoreWait;
osalHandler.SemaphoreTimedWait = Osal_SemaphoreTimedWait;
osalHandler.SemaphorePost = Osal_SemaphorePost;
osalHandler.Malloc = Osal_Malloc;
osalHandler.Free = Osal_Free;
osalHandler.GetTimeMs = Osal_GetTimeMs;
osalHandler.GetTimeUs = Osal_GetTimeUs;
printConsole.func = DjiUser_PrintConsole;
printConsole.consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO;
printConsole.isSupportColor = true;
localRecordConsole.consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_DEBUG;
localRecordConsole.func = DjiUser_LocalWrite;
localRecordConsole.isSupportColor = false;
uartHandler.UartInit = HalUart_Init;
uartHandler.UartDeInit = HalUart_DeInit;
uartHandler.UartWriteData = HalUart_WriteData;
uartHandler.UartReadData = HalUart_ReadData;
uartHandler.UartGetStatus = HalUart_GetStatus;
usbBulkHandler.UsbBulkInit = HalUsbBulk_Init;
usbBulkHandler.UsbBulkDeInit = HalUsbBulk_DeInit;
usbBulkHandler.UsbBulkWriteData = HalUsbBulk_WriteData;
usbBulkHandler.UsbBulkReadData = HalUsbBulk_ReadData;
usbBulkHandler.UsbBulkGetDeviceInfo = HalUsbBulk_GetDeviceInfo;
fileSystemHandler.FileOpen = Osal_FileOpen,
fileSystemHandler.FileClose = Osal_FileClose,
fileSystemHandler.FileWrite = Osal_FileWrite,
fileSystemHandler.FileRead = Osal_FileRead,
fileSystemHandler.FileSync = Osal_FileSync,
fileSystemHandler.FileSeek = Osal_FileSeek,
fileSystemHandler.DirOpen = Osal_DirOpen,
fileSystemHandler.DirClose = Osal_DirClose,
fileSystemHandler.DirRead = Osal_DirRead,
fileSystemHandler.Mkdir = Osal_Mkdir,
fileSystemHandler.Unlink = Osal_Unlink,
fileSystemHandler.Rename = Osal_Rename,
fileSystemHandler.Stat = Osal_Stat,
returnCode = DjiPlatform_RegOsalHandler(&osalHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Register osal handler error.");
}
returnCode = DjiPlatform_RegHalUartHandler(&uartHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
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");
}
returnCode = DjiPlatform_RegFileSystemHandler(&fileSystemHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Register osal filesystem handler error.");
}
if (DjiUser_LocalWriteFsInit(DJI_LOG_PATH) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("File system init error.");
}
returnCode = DjiLogger_AddConsole(&printConsole);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Add printf console error.");
}
returnCode = DjiLogger_AddConsole(&localRecordConsole);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Add printf console error.");
}
}
void Application::DjiUser_ApplicationStart()
{
T_DjiUserInfo userInfo;
T_DjiReturnCode returnCode;
T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo;
T_DjiFirmwareVersion firmwareVersion = {
.majorVersion = 1,
.minorVersion = 0,
.modifyVersion = 0,
.debugVersion = 0,
};
// attention: when the program is hand up ctrl-c will generate the coredump file
signal(SIGTERM, DjiUser_NormalExitHandler);
returnCode = DjiUser_FillInUserInfo(&userInfo);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Fill user info error, please check user info config.");
}
returnCode = DjiCore_Init(&userInfo);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Core init error.");
}
returnCode = DjiAircraftInfo_GetBaseInfo(&aircraftInfoBaseInfo);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Get aircraft base info error.");
}
if (aircraftInfoBaseInfo.mountPosition != DJI_MOUNT_POSITION_EXTENSION_PORT) {
throw std::runtime_error("Please run this sample on extension port.");
}
returnCode = DjiCore_SetAlias("PSDK_APPALIAS");
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Set alias error.");
}
returnCode = DjiCore_SetFirmwareVersion(firmwareVersion);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Set firmware version error.");
}
returnCode = DjiCore_SetSerialNumber("PSDK12345678XX");
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Set serial number error");
}
returnCode = DjiCore_ApplicationStart();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Start sdk application error.");
}
USER_LOG_INFO("Application start.");
}
T_DjiReturnCode Application::DjiUser_PrintConsole(const uint8_t *data, uint16_t dataLen)
{
printf("%s", data);
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
T_DjiReturnCode Application::DjiUser_LocalWrite(const uint8_t *data, uint16_t dataLen)
{
int32_t realLen;
if (s_djiLogFile == nullptr) {
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
realLen = fwrite(data, 1, dataLen, s_djiLogFile);
fflush(s_djiLogFile);
if (realLen == dataLen) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
} else {
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
}
T_DjiReturnCode Application::DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo)
{
memset(userInfo->appName, 0, sizeof(userInfo->appName));
memset(userInfo->appId, 0, sizeof(userInfo->appId));
memset(userInfo->appKey, 0, sizeof(userInfo->appKey));
memset(userInfo->appLicense, 0, sizeof(userInfo->appLicense));
memset(userInfo->developerAccount, 0, sizeof(userInfo->developerAccount));
memset(userInfo->baudRate, 0, sizeof(userInfo->baudRate));
if (strlen(USER_APP_NAME) >= sizeof(userInfo->appName) ||
strlen(USER_APP_ID) > sizeof(userInfo->appId) ||
strlen(USER_APP_KEY) > sizeof(userInfo->appKey) ||
strlen(USER_APP_LICENSE) > sizeof(userInfo->appLicense) ||
strlen(USER_DEVELOPER_ACCOUNT) >= sizeof(userInfo->developerAccount) ||
strlen(USER_BAUD_RATE) > sizeof(userInfo->baudRate)) {
USER_LOG_ERROR("Length of user information string is beyond limit. Please check.");
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}
if (!strcmp(USER_APP_NAME, "your_app_name") ||
!strcmp(USER_APP_ID, "your_app_id") ||
!strcmp(USER_APP_KEY, "your_app_key") ||
!strcmp(USER_BAUD_RATE, "your_app_license") ||
!strcmp(USER_DEVELOPER_ACCOUNT, "your_developer_account") ||
!strcmp(USER_BAUD_RATE, "your_baud_rate")) {
USER_LOG_ERROR(
"Please fill in correct user information to 'samples/sample_c++/platform/linux/manifold2/application/dji_sdk_app_info.h' file.");
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}
strncpy(userInfo->appName, USER_APP_NAME, sizeof(userInfo->appName) - 1);
memcpy(userInfo->appId, USER_APP_ID, USER_UTIL_MIN(sizeof(userInfo->appId), strlen(USER_APP_ID)));
memcpy(userInfo->appKey, USER_APP_KEY, USER_UTIL_MIN(sizeof(userInfo->appKey), strlen(USER_APP_KEY)));
memcpy(userInfo->appLicense, USER_APP_LICENSE,
USER_UTIL_MIN(sizeof(userInfo->appLicense), strlen(USER_APP_LICENSE)));
memcpy(userInfo->baudRate, USER_BAUD_RATE, USER_UTIL_MIN(sizeof(userInfo->baudRate), strlen(USER_BAUD_RATE)));
strncpy(userInfo->developerAccount, USER_DEVELOPER_ACCOUNT, sizeof(userInfo->developerAccount) - 1);
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
T_DjiReturnCode Application::DjiUser_LocalWriteFsInit(const char *path)
{
T_DjiReturnCode djiReturnCode = DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
char filePath[DJI_LOG_PATH_MAX_SIZE];
char systemCmd[DJI_SYSTEM_CMD_STR_MAX_SIZE];
char folderName[DJI_LOG_FOLDER_NAME_MAX_SIZE];
time_t currentTime = time(nullptr);
struct tm *localTime = localtime(&currentTime);
uint16_t logFileIndex = 0;
uint16_t currentLogFileIndex;
uint8_t ret;
if (localTime == nullptr) {
printf("Get local time error.\r\n");
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
if (access(DJI_LOG_FOLDER_NAME, F_OK) != 0) {
sprintf(folderName, "mkdir %s", DJI_LOG_FOLDER_NAME);
ret = system(folderName);
if (ret != 0) {
printf("Create new log folder error, ret:%d.\r\n", ret);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
}
s_djiLogFileCnt = fopen(DJI_LOG_INDEX_FILE_NAME, "rb+");
if (s_djiLogFileCnt == nullptr) {
s_djiLogFileCnt = fopen(DJI_LOG_INDEX_FILE_NAME, "wb+");
if (s_djiLogFileCnt == nullptr) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
} else {
ret = fseek(s_djiLogFileCnt, 0, SEEK_SET);
if (ret != 0) {
printf("Seek log count file error, ret: %d, errno: %d.\r\n", ret, errno);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
ret = fread((uint16_t * ) & logFileIndex, 1, sizeof(uint16_t), s_djiLogFileCnt);
if (ret != sizeof(uint16_t)) {
printf("Read log file index error.\r\n");
}
}
currentLogFileIndex = logFileIndex;
logFileIndex++;
ret = fseek(s_djiLogFileCnt, 0, SEEK_SET);
if (ret != 0) {
printf("Seek log file error, ret: %d, errno: %d.\r\n", ret, errno);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
ret = fwrite((uint16_t * ) & logFileIndex, 1, sizeof(uint16_t), s_djiLogFileCnt);
if (ret != sizeof(uint16_t)) {
printf("Write log file index error.\r\n");
fclose(s_djiLogFileCnt);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
fclose(s_djiLogFileCnt);
sprintf(filePath, "%s_%04d_%04d%02d%02d_%02d-%02d-%02d.log", path, currentLogFileIndex,
localTime->tm_year + 1900, localTime->tm_mon + 1, localTime->tm_mday,
localTime->tm_hour, localTime->tm_min, localTime->tm_sec);
s_djiLogFile = fopen(filePath, "wb+");
if (s_djiLogFile == nullptr) {
USER_LOG_ERROR("Open filepath time error.");
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
if (logFileIndex >= DJI_LOG_MAX_COUNT) {
sprintf(systemCmd, "rm -rf %s_%04d*.log", path, currentLogFileIndex - DJI_LOG_MAX_COUNT);
ret = system(systemCmd);
if (ret != 0) {
printf("Remove file error, ret:%d.\r\n", ret);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
}
return djiReturnCode;
}
static void DjiUser_NormalExitHandler(int signalNum)
{
USER_UTIL_UNUSED(signalNum);
exit(0);
}
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/

View File

@ -0,0 +1,67 @@
/**
********************************************************************
* @file dji_application.hpp
* @brief This is the header file for "dji_application.cpp", 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 APPLICATION_H
#define APPLICATION_H
/* Includes ------------------------------------------------------------------*/
#include <iostream>
#include <fstream>
#include "dji_typedef.h"
#include "dji_core.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
using namespace std;
class Application {
public:
Application(int argc, char **argv);
~Application();
private:
static void DjiUser_SetupEnvironment();
static void DjiUser_ApplicationStart();
static T_DjiReturnCode DjiUser_PrintConsole(const uint8_t *data, uint16_t dataLen);
static T_DjiReturnCode DjiUser_LocalWrite(const uint8_t *data, uint16_t dataLen);
static T_DjiReturnCode DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo);
static T_DjiReturnCode DjiUser_LocalWriteFsInit(const char *path);
};
/* Exported functions --------------------------------------------------------*/
#ifdef __cplusplus
}
#endif
#endif // APPLICATION_H
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/

View File

@ -0,0 +1,55 @@
/**
********************************************************************
* @file dji_sdk_app_info.h
* @brief This is the header file for defining the structure and (exported) function prototypes.
*
* @copyright (c) 2018 DJI. All rights reserved.
*
* All information contained herein is, and remains, the property of DJI.
* The intellectual and technical concepts contained herein are proprietary
* to DJI and may be covered by U.S. and foreign patents, patents in process,
* and protected by trade secret or copyright law. Dissemination of this
* information, including but not limited to data and other proprietary
* material(s) incorporated within the information, in any form, is strictly
* prohibited without the express written consent of DJI.
*
* If you receive this source code without DJIs authorization, you may not
* further disseminate the information, and you must immediately remove the
* source code and notify DJI of its removal. DJI reserves the right to pursue
* legal actions against you for any loss(es) or damage(s) caused by your
* failure to do so.
*
*********************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef DJI_SDK_APP_INFO_H
#define DJI_SDK_APP_INFO_H
/* Includes ------------------------------------------------------------------*/
#ifdef __cplusplus
extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
// ATTENTION: User must goto https://developer.dji.com/user/apps/#all to create your own dji sdk application, get dji sdk application
// information then fill in the application information here.
#define USER_APP_NAME "your_app_name"
#define USER_APP_ID "your_app_id"
#define USER_APP_KEY "your_app_key"
#define USER_APP_LICENSE "your_app_license"
#define USER_DEVELOPER_ACCOUNT "your_developer_account"
#define USER_BAUD_RATE "460800"
/* Exported types ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
#ifdef __cplusplus
}
#endif
#endif // DJI_SDK_APP_INFO_H
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/

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

@ -0,0 +1,227 @@
/**
********************************************************************
* @file main.cpp
* @brief
*
* @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.
*
*********************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include <liveview/test_liveview_entry.hpp>
#include <perception/test_perception_entry.hpp>
#include <flight_control/test_flight_control.h>
#include <gimbal/test_gimbal_entry.hpp>
#include <hms/test_hms.h>
#include <waypoint_v2/test_waypoint_v2.h>
#include <waypoint_v3/test_waypoint_v3.h>
#include <gimbal_manager/test_gimbal_manager.h>
#include "application.hpp"
#include "fc_subscription/test_fc_subscription.h"
#include <gimbal_emu/test_payload_gimbal_emu.h>
#include <camera_emu/test_payload_cam_emu_media.h>
#include <camera_emu/test_payload_cam_emu_base.h>
#include <dji_logger.h>
#include "widget/test_widget.h"
#include "widget/test_widget_speaker.h"
#include <power_management/test_power_management.h>
#include "data_transmission/test_data_transmission.h"
#include <camera_manager/test_camera_manager.h>
#include "camera_manager/test_camera_manager_entry.h"
/* Private constants ---------------------------------------------------------*/
/* Private types -------------------------------------------------------------*/
/* Private values -------------------------------------------------------------*/
/* Private functions declaration ---------------------------------------------*/
static T_DjiReturnCode DjiTest_HighPowerApplyPinInit();
static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState);
/* Exported functions definition ---------------------------------------------*/
int main(int argc, char **argv)
{
Application application(argc, argv);
char inputChar;
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
T_DjiReturnCode returnCode;
T_DjiTestApplyHighPowerHandler applyHighPowerHandler;
start:
std::cout
<< "\n"
<< "| Available commands: |\n"
<< "| [0] Fc subscribe sample - subscribe quaternion and gps data |\n"
<< "| [1] Flight controller sample - take off landing |\n"
<< "| [2] Flight controller sample - take off position ctrl landing |\n"
<< "| [3] Flight controller sample - take off go home force landing |\n"
<< "| [4] Flight controller sample - take off velocity ctrl landing |\n"
<< "| [5] Flight controller sample - arrest flying |\n"
<< "| [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 (not support on M300 RTK) |\n"
<< "| [a] Gimbal manager sample |\n"
<< "| [c] Camera stream view sample - display the camera video stream |\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"
<< "| [k] Run camera manager sample - you can test camera's functions interactively |\n"
<< std::endl;
std::cin >> inputChar;
switch (inputChar) {
case '0':
DjiTest_FcSubscriptionRunSample();
break;
case '1':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_LANDING);
break;
case '2':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_POSITION_CTRL_LANDING);
break;
case '3':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_GO_HOME_FORCE_LANDING);
break;
case '4':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_VELOCITY_CTRL_LANDING);
break;
case '5':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_ARREST_FLYING);
break;
case '6':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SET_GET_PARAM);
break;
case '7':
DjiTest_HmsRunSample();
break;
case '8':
DjiTest_WaypointV2RunSample();
break;
case '9':
DjiTest_WaypointV3RunSample();
break;
case 'a':
DjiUser_RunGimbalManagerSample();
break;
case 'c':
DjiUser_RunCameraStreamViewSample();
break;
case 'd':
DjiUser_RunStereoVisionViewSample();
break;
case 'e':
returnCode = DjiTest_CameraEmuBaseStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("camera emu common init error");
break;
}
if (DjiPlatform_GetSocketHandler() != nullptr) {
returnCode = DjiTest_CameraEmuMediaStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("camera emu media init error");
break;
}
}
USER_LOG_INFO("Start camera all feautes sample successfully");
break;
case 'f':
if (DjiTest_GimbalStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("psdk gimbal init error");
break;
}
USER_LOG_INFO("Start gimbal all feautes sample successfully");
break;
case 'g':
returnCode = DjiTest_WidgetStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("widget sample init error");
break;
}
USER_LOG_INFO("Start widget all feautes sample successfully");
break;
case 'h':
returnCode = DjiTest_WidgetSpeakerStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("widget speaker test init error");
break;
}
USER_LOG_INFO("Start widget speaker sample successfully");
break;
case 'i':
applyHighPowerHandler.pinInit = DjiTest_HighPowerApplyPinInit;
applyHighPowerHandler.pinWrite = DjiTest_WriteHighPowerApplyPin;
returnCode = DjiTest_RegApplyHighPowerHandler(&applyHighPowerHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("regsiter apply high power handler error");
break;
}
returnCode = DjiTest_PowerManagementStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("power management init error");
break;
}
USER_LOG_INFO("Start power management sample successfully");
break;
case 'j':
returnCode = DjiTest_DataTransmissionStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("data transmission sample init error");
break;
}
USER_LOG_INFO("Start data transmission sample successfully");
break;
case 'k':
DjiUser_RunCameraManagerSample();
break;
default:
break;
}
osalHandler->TaskSleepMs(2000);
goto start;
}
/* Private functions definition-----------------------------------------------*/
static T_DjiReturnCode DjiTest_HighPowerApplyPinInit()
{
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState)
{
//attention: please pull up the HWPR pin state by hardware.
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/

View File

@ -0,0 +1,92 @@
/**
********************************************************************
* @file hal_network.c
* @version V2.0.0
* @date 3/27/20
* @brief
*
* @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.
*
*********************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "string.h"
#include "stdlib.h"
#include "stdio.h"
#include "hal_network.h"
#include "dji_logger.h"
/* Private constants ---------------------------------------------------------*/
/* Private types -------------------------------------------------------------*/
/* Private values -------------------------------------------------------------*/
/* Private functions declaration ---------------------------------------------*/
/* Exported functions definition ---------------------------------------------*/
T_DjiReturnCode HalNetWork_Init(const char *ipAddr, const char *netMask, T_DjiNetworkHandle *halObj)
{
int32_t ret;
char cmdStr[LINUX_CMD_STR_MAX_SIZE];
if (ipAddr == NULL || netMask == NULL) {
USER_LOG_ERROR("hal network config param error");
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}
//Attention: need root permission to config ip addr and netmask.
memset(cmdStr, 0, sizeof(cmdStr));
snprintf(cmdStr, sizeof(cmdStr), "ifconfig %s up", LINUX_NETWORK_DEV);
ret = system(cmdStr);
if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Can't open the network."
"Probably the program not execute with root permission."
"Please use the root permission to execute the program.");
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
snprintf(cmdStr, sizeof(cmdStr), "ifconfig %s %s netmask %s", LINUX_NETWORK_DEV, ipAddr, netMask);
ret = system(cmdStr);
if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Can't config the ip address of network."
"Probably the program not execute with root permission."
"Please use the root permission to execute the program.");
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
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

@ -0,0 +1,73 @@
/**
********************************************************************
* @file hal_network.h
* @brief This is the header file for "hal_network.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 HAL_NETWORK_H
#define HAL_NETWORK_H
/* Includes ------------------------------------------------------------------*/
#include "dji_platform.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
/** @attention User can config network card name here, if your device is not MF2C/G, please comment below and add your
* NIC name micro define as #define 'LINUX_NETWORK_DEV "your NIC name"'.
*/
#ifdef PLATFORM_ARCH_x86_64
#define LINUX_NETWORK_DEV "enxf8e43b7bbc2c"
#else
#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)
/* Exported types ------------------------------------------------------------*/
/* 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
}
#endif
#endif // HAL_NETWORK_H
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/

View File

@ -0,0 +1,260 @@
/**
********************************************************************
* @file hal_uart.c
* @brief
*
* @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.
*
*********************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include <dji_logger.h>
#include "hal_uart.h"
/* Private constants ---------------------------------------------------------*/
#define UART_DEV_NAME_STR_SIZE (128)
#define DJI_SYSTEM_CMD_STR_MAX_SIZE (64)
#define DJI_SYSTEM_RESULT_STR_MAX_SIZE (128)
/* Private types -------------------------------------------------------------*/
typedef struct {
int uartFd;
} T_UartHandleStruct;
/* Private values -------------------------------------------------------------*/
/* Private functions declaration ---------------------------------------------*/
/* Exported functions definition ---------------------------------------------*/
T_DjiReturnCode HalUart_Init(E_DjiHalUartNum uartNum, uint32_t baudRate, T_DjiUartHandle *uartHandle)
{
T_UartHandleStruct *uartHandleStruct;
struct termios options;
struct flock lock;
T_DjiReturnCode returnCode = DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
char uartName[UART_DEV_NAME_STR_SIZE];
char systemCmd[DJI_SYSTEM_CMD_STR_MAX_SIZE];
char *ret = NULL;
char lineBuf[DJI_SYSTEM_RESULT_STR_MAX_SIZE] = {0};
FILE *fp;
uartHandleStruct = malloc(sizeof(T_UartHandleStruct));
if (uartHandleStruct == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_MEMORY_ALLOC_FAILED;
}
if (uartNum == DJI_HAL_UART_NUM_0) {
strcpy(uartName, LINUX_UART_DEV1);
} else if (uartNum == DJI_HAL_UART_NUM_1) {
strcpy(uartName, LINUX_UART_DEV2);
} else {
goto free_uart_handle;
}
#ifdef USE_CLION_DEBUG
sprintf(systemCmd, "ls -l %s", uartName);
fp = popen(systemCmd, "r");
if (fp == NULL) {
goto free_uart_handle;
}
ret = fgets(lineBuf, sizeof(lineBuf), fp);
if (ret == NULL) {
goto close_fp;
}
if (strstr(lineBuf, "crwxrwxrwx") == NULL) {
USER_LOG_ERROR("Can't operation the device. "
"Probably the device has not operation permission. "
"Please execute command 'sudo chmod 777 %s' to add permission. ", uartName);
goto close_fp;
}
#else
sprintf(systemCmd, "chmod 777 %s", uartName);
fp = popen(systemCmd, "r");
if (fp == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
#endif
uartHandleStruct->uartFd = open(uartName, (unsigned) O_RDWR | (unsigned) O_NOCTTY | (unsigned) O_NDELAY);
if (uartHandleStruct->uartFd == -1) {
goto close_fp;
}
// Forbid multiple psdk programs to access the serial port
lock.l_type = F_WRLCK;
lock.l_pid = getpid();
lock.l_whence = SEEK_SET;
lock.l_start = 0;
lock.l_len = 0;
if (fcntl(uartHandleStruct->uartFd, F_GETLK, &lock) < 0) {
goto close_uart_fd;
}
if (lock.l_type != F_UNLCK) {
goto close_uart_fd;
}
lock.l_type = F_WRLCK;
lock.l_pid = getpid();
lock.l_whence = SEEK_SET;
lock.l_start = 0;
lock.l_len = 0;
if (fcntl(uartHandleStruct->uartFd, F_SETLKW, &lock) < 0) {
goto close_uart_fd;
}
if (tcgetattr(uartHandleStruct->uartFd, &options) != 0) {
goto close_uart_fd;
}
switch (baudRate) {
case 115200:
cfsetispeed(&options, B115200);
cfsetospeed(&options, B115200);
break;
case 230400:
cfsetispeed(&options, B230400);
cfsetospeed(&options, B230400);
break;
case 460800:
cfsetispeed(&options, B460800);
cfsetospeed(&options, B460800);
break;
case 921600:
cfsetispeed(&options, B921600);
cfsetospeed(&options, B921600);
break;
case 1000000:
cfsetispeed(&options, B1000000);
cfsetospeed(&options, B1000000);
break;
default:
goto close_uart_fd;
}
options.c_cflag |= (unsigned) CLOCAL;
options.c_cflag |= (unsigned) CREAD;
options.c_cflag &= ~(unsigned) CRTSCTS;
options.c_cflag &= ~(unsigned) CSIZE;
options.c_cflag |= (unsigned) CS8;
options.c_cflag &= ~(unsigned) PARENB;
options.c_iflag &= ~(unsigned) INPCK;
options.c_cflag &= ~(unsigned) CSTOPB;
options.c_oflag &= ~(unsigned) OPOST;
options.c_lflag &= ~((unsigned) ICANON | (unsigned) ECHO | (unsigned) ECHOE | (unsigned) ISIG);
options.c_iflag &= ~((unsigned) BRKINT | (unsigned) ICRNL | (unsigned) INPCK | (unsigned) ISTRIP | (unsigned) IXON);
options.c_cc[VTIME] = 0;
options.c_cc[VMIN] = 0;
tcflush(uartHandleStruct->uartFd, TCIFLUSH);
if (tcsetattr(uartHandleStruct->uartFd, TCSANOW, &options) != 0) {
goto close_uart_fd;
}
*uartHandle = uartHandleStruct;
pclose(fp);
return returnCode;
close_uart_fd:
close(uartHandleStruct->uartFd);
close_fp:
pclose(fp);
free_uart_handle:
free(uartHandleStruct);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
T_DjiReturnCode HalUart_DeInit(T_DjiUartHandle uartHandle)
{
int32_t ret;
T_UartHandleStruct *uartHandleStruct = (T_UartHandleStruct *) uartHandle;
if (uartHandle == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
ret = close(uartHandleStruct->uartFd);
if (ret < 0) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
free(uartHandleStruct);
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf, uint32_t len, uint32_t *realLen)
{
int32_t ret;
T_UartHandleStruct *uartHandleStruct = (T_UartHandleStruct *) uartHandle;
if (uartHandle == NULL || buf == NULL || len == 0 || realLen == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}
ret = write(uartHandleStruct->uartFd, buf, len);
if (ret >= 0) {
*realLen = ret;
} else {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen)
{
int32_t ret;
T_UartHandleStruct *uartHandleStruct = (T_UartHandleStruct *) uartHandle;
if (uartHandle == NULL || buf == NULL || len == 0 || realLen == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}
ret = read(uartHandleStruct->uartFd, buf, len);
if (ret >= 0) {
*realLen = ret;
} else {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *status)
{
if (uartNum == DJI_HAL_UART_NUM_0) {
status->isConnect = true;
} else if (uartNum == DJI_HAL_UART_NUM_1) {
status->isConnect = true;
} else {
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
/* Private functions definition-----------------------------------------------*/
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/

View File

@ -0,0 +1,65 @@
/**
********************************************************************
* @file hal_uart.h
* @brief This is the header file for "hal_uart.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 HAL_UART_H
#define HAL_UART_H
/* Includes ------------------------------------------------------------------*/
#include "stdint.h"
#include <stdio.h>
#include <unistd.h>
#include <fcntl.h>
#include <termios.h>
#include <unistd.h>
#include <string.h>
#include "stdlib.h"
#include "dji_platform.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
//User can config dev based on there environmental conditions
#define LINUX_UART_DEV1 "/dev/ttyUSB0"
#define LINUX_UART_DEV2 "/dev/ttyACM0"
/* Exported types ------------------------------------------------------------*/
/* 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
}
#endif
#endif // HAL_UART_H
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/

View File

@ -0,0 +1,224 @@
/**
********************************************************************
* @file hal_usb_bulk.c
* @brief
*
* @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.
*
*********************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "hal_usb_bulk.h"
#include "dji_logger.h"
/* Private constants ---------------------------------------------------------*/
#define LINUX_USB_BULK_TRANSFER_TIMEOUT_MS (50)
#define LINUX_USB_BULK_TRANSFER_WAIT_FOREVER (-1)
/* Private types -------------------------------------------------------------*/
typedef struct {
#ifdef LIBUSB_INSTALLED
libusb_device_handle *handle;
#else
void *handle;
#endif
int32_t ep1;
int32_t ep2;
uint32_t interfaceNum;
T_DjiHalUsbBulkInfo usbBulkInfo;
} T_HalUsbBulkObj;
/* Private values -------------------------------------------------------------*/
/* Private functions declaration ---------------------------------------------*/
/* Exported functions definition ---------------------------------------------*/
T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHandle *usbBulkHandle)
{
int32_t ret;
struct libusb_device_handle *handle = NULL;
*usbBulkHandle = malloc(sizeof(T_HalUsbBulkObj));
if (*usbBulkHandle == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
if (usbBulkInfo.isUsbHost == true) {
#ifdef LIBUSB_INSTALLED
ret = libusb_init(NULL);
if (ret < 0) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
handle = libusb_open_device_with_vid_pid(NULL, usbBulkInfo.vid, usbBulkInfo.pid);
if (handle == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
ret = libusb_claim_interface(handle, usbBulkInfo.channelInfo.interfaceNum);
if (ret != LIBUSB_SUCCESS) {
printf("libusb claim interface error");
libusb_close(handle);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle;
memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo));
#endif
} else {
((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle;
memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo));
((T_HalUsbBulkObj *) *usbBulkHandle)->interfaceNum = usbBulkInfo.channelInfo.interfaceNum;
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_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;
}
}
}
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle)
{
struct libusb_device_handle *handle = NULL;
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
if (usbBulkHandle == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
#ifdef LIBUSB_INSTALLED
libusb_release_interface(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum);
osalHandler->TaskSleepMs(100);
libusb_exit(NULL);
#endif
} else {
close(((T_HalUsbBulkObj *) usbBulkHandle)->ep1);
close(((T_HalUsbBulkObj *) usbBulkHandle)->ep2);
}
free(usbBulkHandle);
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
T_DjiReturnCode HalUsbBulk_WriteData(T_DjiUsbBulkHandle usbBulkHandle, const uint8_t *buf, uint32_t len,
uint32_t *realLen)
{
int32_t ret;
int32_t actualLen;
struct libusb_device_handle *handle = NULL;
if (usbBulkHandle == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
#ifdef LIBUSB_INSTALLED
ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointOut,
(uint8_t *) buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_TIMEOUT_MS);
if (ret < 0) {
USER_LOG_ERROR("Write usb bulk data failed, errno = %d", ret);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
*realLen = actualLen;
#endif
} else {
*realLen = write(((T_HalUsbBulkObj *) usbBulkHandle)->ep1, buf, len);
}
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len,
uint32_t *realLen)
{
int32_t ret;
struct libusb_device_handle *handle = NULL;
int32_t actualLen;
if (usbBulkHandle == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
#ifdef LIBUSB_INSTALLED
ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointIn,
buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_WAIT_FOREVER);
if (ret < 0) {
USER_LOG_ERROR("Read usb bulk data failed, errno = %d", ret);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
*realLen = actualLen;
#endif
} else {
*realLen = read(((T_HalUsbBulkObj *) usbBulkHandle)->ep2, buf, len);
}
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo)
{
//attention: this interface only be called in usb device mode.
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;
}
/* Private functions definition-----------------------------------------------*/
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/

View File

@ -0,0 +1,92 @@
/**
********************************************************************
* @file hal_usb_bulk.h
* @brief This is the header file for "hal_usb_bulk.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 HAL_USB_BULK_H
#define HAL_USB_BULK_H
/* Includes ------------------------------------------------------------------*/
#include "stdint.h"
#include <stdio.h>
#include <unistd.h>
#include <fcntl.h>
#include <termios.h>
#include <unistd.h>
#include <string.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <arpa/inet.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 (7)
#define LINUX_USB_BULK1_END_POINT_IN (0x88)
#define LINUX_USB_BULK1_END_POINT_OUT (5)
#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 (8)
#define LINUX_USB_BULK2_END_POINT_IN (0x89)
#define LINUX_USB_BULK2_END_POINT_OUT (6)
#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_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo);
#ifdef __cplusplus
}
#endif
#endif // HAL_USB_BULK_H
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/