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