NEW: release DJI Payload-SDK version 3.4
Signed-off-by: DJI-Martin <DJI-Martin@dji.com>
This commit is contained in:
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* 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****/
|
||||
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef 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******/
|
||||
129
samples/sample_c++/module_sample/gimbal/test_gimbal_entry.cpp
Normal file
129
samples/sample_c++/module_sample/gimbal/test_gimbal_entry.cpp
Normal 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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* 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****/
|
||||
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef 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******/
|
||||
Binary file not shown.
@ -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)
|
||||
|
||||
@ -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;
|
||||
};
|
||||
|
||||
@ -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) {
|
||||
|
||||
@ -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));
|
||||
}
|
||||
}
|
||||
|
||||
@ -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");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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;
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
|
||||
@ -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)
|
||||
|
||||
@ -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****/
|
||||
|
||||
@ -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;
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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>
|
||||
|
||||
134
samples/sample_c++/platform/linux/nvidia_jeston/CMakeLists.txt
Normal file
134
samples/sample_c++/platform/linux/nvidia_jeston/CMakeLists.txt
Normal 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 ()
|
||||
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* 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(¤tTime);
|
||||
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****/
|
||||
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef 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******/
|
||||
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef DJI_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******/
|
||||
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef DJI_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******/
|
||||
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* 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****/
|
||||
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* 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****/
|
||||
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef 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******/
|
||||
260
samples/sample_c++/platform/linux/nvidia_jeston/hal/hal_uart.c
Normal file
260
samples/sample_c++/platform/linux/nvidia_jeston/hal/hal_uart.c
Normal 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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* 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****/
|
||||
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef 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******/
|
||||
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* 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****/
|
||||
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef 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******/
|
||||
@ -33,6 +33,10 @@
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define TEST_CAMERA_MANAGER_MEDIA_FILE_NAME_MAX_SIZE 256
|
||||
#define TEST_CAMERA_MANAGER_MEDIA_DOWNLOAD_FILE_NUM 5
|
||||
#define CAMERA_MANAGER_SUBSCRIPTION_FREQ 5
|
||||
|
||||
#define TEST_CAMERA_MAX_INFRARED_ZOOM_FACTOR 8
|
||||
#define TEST_CAMERA_MIN_INFRARED_ZOOM_FACTOR 2
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
typedef struct {
|
||||
@ -63,13 +67,17 @@ static T_DjiCameraManagerFileList s_meidaFileList;
|
||||
static uint32_t downloadStartMs = 0;
|
||||
static uint32_t downloadEndMs = 0;
|
||||
static char downloadFileName[TEST_CAMERA_MANAGER_MEDIA_FILE_NAME_MAX_SIZE] = {0};
|
||||
static uint32_t nextDownloadFileIndex = 0;
|
||||
static uint32_t s_nextDownloadFileIndex = 0;
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
static uint8_t DjiTest_CameraManagerGetCameraTypeIndex(E_DjiCameraType cameraType);
|
||||
static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_DjiMountPosition position);
|
||||
static T_DjiReturnCode DjiTest_CameraManagerDownloadFileDataCallback(T_DjiDownloadFilePacketInfo packetInfo,
|
||||
const uint8_t *data, uint16_t len);
|
||||
static T_DjiReturnCode DjiTest_CameraManagerGetAreaThermometryData(E_DjiMountPosition position);
|
||||
static T_DjiReturnCode DjiTest_CameraManagerGetPointThermometryData(E_DjiMountPosition position);
|
||||
|
||||
static T_DjiReturnCode DjiTest_CameraManagerGetLidarRangingInfo(E_DjiMountPosition position);
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
/*! @brief Sample to set EV for camera, using async api
|
||||
@ -480,6 +488,7 @@ T_DjiReturnCode DjiTest_CameraManagerStartShootSinglePhoto(E_DjiMountPosition po
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
E_DjiCameraManagerWorkMode workMode;
|
||||
|
||||
/*!< set camera work mode as shoot photo */
|
||||
USER_LOG_INFO("Set mounted position %d camera's work mode as shoot-photo mode", position);
|
||||
@ -491,6 +500,17 @@ T_DjiReturnCode DjiTest_CameraManagerStartShootSinglePhoto(E_DjiMountPosition po
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
osalHandler->TaskSleepMs(1000);
|
||||
|
||||
returnCode = DjiCameraManager_GetMode(position, &workMode);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS &&
|
||||
returnCode != DJI_ERROR_CAMERA_MANAGER_MODULE_CODE_UNSUPPORTED_COMMAND) {
|
||||
USER_LOG_ERROR("get mounted position %d camera's work mode failed,"
|
||||
" error code :0x%08X", position, returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
USER_LOG_INFO("Camera current workmode is %d", workMode);
|
||||
|
||||
/*!< set shoot-photo mode */
|
||||
USER_LOG_INFO("Set mounted position %d camera's shoot photo mode as single-photo mode", position);
|
||||
returnCode = DjiCameraManager_SetShootPhotoMode(position, DJI_CAMERA_MANAGER_SHOOT_PHOTO_MODE_SINGLE);
|
||||
@ -530,6 +550,7 @@ T_DjiReturnCode DjiTest_CameraManagerStartShootBurstPhoto(E_DjiMountPosition pos
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
E_DjiCameraManagerWorkMode workMode;
|
||||
|
||||
/*!< set camera work mode as shoot photo */
|
||||
USER_LOG_INFO("set mounted position %d camera's work mode as shoot photo mode.", position);
|
||||
@ -540,6 +561,17 @@ T_DjiReturnCode DjiTest_CameraManagerStartShootBurstPhoto(E_DjiMountPosition pos
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
osalHandler->TaskSleepMs(1000);
|
||||
|
||||
returnCode = DjiCameraManager_GetMode(position, &workMode);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS &&
|
||||
returnCode != DJI_ERROR_CAMERA_MANAGER_MODULE_CODE_UNSUPPORTED_COMMAND) {
|
||||
USER_LOG_ERROR("get mounted position %d camera's work mode failed,"
|
||||
" error code :0x%08X", position, returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
USER_LOG_INFO("Camera current workmode is %d", workMode);
|
||||
|
||||
/*!< set shoot-photo mode */
|
||||
USER_LOG_INFO("Set mounted position %d camera's shoot photo mode as burst-photo mode", position);
|
||||
returnCode = DjiCameraManager_SetShootPhotoMode(position, DJI_CAMERA_MANAGER_SHOOT_PHOTO_MODE_BURST);
|
||||
@ -592,6 +624,7 @@ T_DjiReturnCode DjiTest_CameraManagerStartShootAEBPhoto(E_DjiMountPosition posit
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
E_DjiCameraManagerWorkMode workMode;
|
||||
|
||||
/*!< set camera work mode as shoot photo */
|
||||
USER_LOG_INFO("set mounted position %d camera's work mode as shoot photo mode.", position);
|
||||
@ -603,6 +636,17 @@ T_DjiReturnCode DjiTest_CameraManagerStartShootAEBPhoto(E_DjiMountPosition posit
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
osalHandler->TaskSleepMs(1000);
|
||||
|
||||
returnCode = DjiCameraManager_GetMode(position, &workMode);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS &&
|
||||
returnCode != DJI_ERROR_CAMERA_MANAGER_MODULE_CODE_UNSUPPORTED_COMMAND) {
|
||||
USER_LOG_ERROR("get mounted position %d camera's work mode failed,"
|
||||
" error code :0x%08X", position, returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
USER_LOG_INFO("Camera current workmode is %d", workMode);
|
||||
|
||||
/*!< set shoot-photo mode */
|
||||
USER_LOG_INFO("Set mounted position %d camera's shoot photo mode as AEB-photo mode", position);
|
||||
returnCode = DjiCameraManager_SetShootPhotoMode(position, DJI_CAMERA_MANAGER_SHOOT_PHOTO_MODE_AEB);
|
||||
@ -654,6 +698,7 @@ T_DjiReturnCode DjiTest_CameraManagerStartShootIntervalPhoto(E_DjiMountPosition
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
E_DjiCameraManagerWorkMode workMode;
|
||||
|
||||
/*!< set camera work mode as shoot photo */
|
||||
USER_LOG_INFO("set mounted position %d camera's work mode as shoot photo mode.", position);
|
||||
@ -666,6 +711,15 @@ T_DjiReturnCode DjiTest_CameraManagerStartShootIntervalPhoto(E_DjiMountPosition
|
||||
|
||||
osalHandler->TaskSleepMs(1000);
|
||||
|
||||
returnCode = DjiCameraManager_GetMode(position, &workMode);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS &&
|
||||
returnCode != DJI_ERROR_CAMERA_MANAGER_MODULE_CODE_UNSUPPORTED_COMMAND) {
|
||||
USER_LOG_ERROR("get mounted position %d camera's work mode failed,"
|
||||
" error code :0x%08X", position, returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
USER_LOG_INFO("Camera current workmode is %d", workMode);
|
||||
|
||||
/*!< set shoot-photo mode */
|
||||
USER_LOG_INFO("Set mounted position %d camera's shoot photo mode as interval-photo mode", position);
|
||||
returnCode = DjiCameraManager_SetShootPhotoMode(position, DJI_CAMERA_MANAGER_SHOOT_PHOTO_MODE_INTERVAL);
|
||||
@ -743,6 +797,9 @@ T_DjiReturnCode DjiTest_CameraManagerStopShootPhoto(E_DjiMountPosition position)
|
||||
T_DjiReturnCode DjiTest_CameraManagerStartRecordVideo(E_DjiMountPosition position)
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
E_DjiCameraManagerWorkMode workMode;
|
||||
|
||||
/*!< set camera work mode as record video */
|
||||
USER_LOG_INFO("set mounted position %d camera's work mode as record-video mode", position);
|
||||
returnCode = DjiCameraManager_SetMode(position, DJI_CAMERA_MANAGER_WORK_MODE_RECORD_VIDEO);
|
||||
@ -753,6 +810,17 @@ T_DjiReturnCode DjiTest_CameraManagerStartRecordVideo(E_DjiMountPosition positio
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
osalHandler->TaskSleepMs(1000);
|
||||
|
||||
returnCode = DjiCameraManager_GetMode(position, &workMode);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS &&
|
||||
returnCode != DJI_ERROR_CAMERA_MANAGER_MODULE_CODE_UNSUPPORTED_COMMAND) {
|
||||
USER_LOG_ERROR("get mounted position %d camera's work mode failed,"
|
||||
" error code :0x%08X", position, returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
USER_LOG_INFO("Camera current workmode is %d", workMode);
|
||||
|
||||
/*!< start to take video */
|
||||
USER_LOG_INFO("Mounted position %d camera start to record video.", position);
|
||||
returnCode = DjiCameraManager_StartRecordVideo(position);
|
||||
@ -797,7 +865,7 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition,
|
||||
T_DjiCameraManagerFocusPosData focusPosData;
|
||||
T_DjiCameraManagerTapZoomPosData tapZoomPosData;
|
||||
|
||||
USER_LOG_INFO("Camera manager sample start");
|
||||
USER_LOG_INFO("Camera manager sample start, cameraManagerSampleSelect %d", cameraManagerSampleSelect);
|
||||
DjiTest_WidgetLogAppend("Camera manager sample start");
|
||||
|
||||
USER_LOG_INFO("--> Step 1: Init camera manager module");
|
||||
@ -835,8 +903,9 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition,
|
||||
USER_LOG_INFO("--> Function a: Set camera shutter speed to 1/100 s");
|
||||
DjiTest_WidgetLogAppend("--> Function a: Set camera shutter speed to 1/100 s");
|
||||
if (cameraType == DJI_CAMERA_TYPE_H20 || cameraType == DJI_CAMERA_TYPE_H20T ||
|
||||
cameraType == DJI_CAMERA_TYPE_M30 || cameraType == DJI_CAMERA_TYPE_M30T ||
|
||||
cameraType == DJI_CAMERA_TYPE_M3E || cameraType == DJI_CAMERA_TYPE_M3T) {
|
||||
cameraType == DJI_CAMERA_TYPE_H20N || cameraType == DJI_CAMERA_TYPE_M30 ||
|
||||
cameraType == DJI_CAMERA_TYPE_M30T || cameraType == DJI_CAMERA_TYPE_M3E ||
|
||||
cameraType == DJI_CAMERA_TYPE_M3T) {
|
||||
USER_LOG_INFO("Set mounted position %d camera's exposure mode to manual mode.",
|
||||
mountPosition);
|
||||
returnCode = DjiTest_CameraManagerSetExposureMode(mountPosition,
|
||||
@ -872,9 +941,10 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition,
|
||||
case E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_APERTURE: {
|
||||
USER_LOG_INFO("--> Function b: Set camera aperture to 400(F/4)");
|
||||
DjiTest_WidgetLogAppend("--> Function b: Set camera aperture to 400(F/4)");
|
||||
if (cameraType == DJI_CAMERA_TYPE_H20 || cameraType == DJI_CAMERA_TYPE_H20T
|
||||
|| cameraType == DJI_CAMERA_TYPE_M30 || cameraType == DJI_CAMERA_TYPE_M30T
|
||||
|| cameraType == DJI_CAMERA_TYPE_M3E || cameraType == DJI_CAMERA_TYPE_M3T) {
|
||||
if (cameraType == DJI_CAMERA_TYPE_H20 || cameraType == DJI_CAMERA_TYPE_H20N
|
||||
|| cameraType == DJI_CAMERA_TYPE_H20T || cameraType == DJI_CAMERA_TYPE_M30
|
||||
|| cameraType == DJI_CAMERA_TYPE_M30T || cameraType == DJI_CAMERA_TYPE_M3E
|
||||
|| cameraType == DJI_CAMERA_TYPE_M3T) {
|
||||
USER_LOG_INFO("Set mounted position %d camera's exposure mode to manual mode.",
|
||||
mountPosition);
|
||||
returnCode = DjiTest_CameraManagerSetExposureMode(mountPosition,
|
||||
@ -1117,13 +1187,54 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition,
|
||||
}
|
||||
break;
|
||||
}
|
||||
case E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_DOWNLOAD_AND_DELETE_MEDIA_FILE:
|
||||
case E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_DOWNLOAD_AND_DELETE_MEDIA_FILE: {
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(mountPosition);
|
||||
#else
|
||||
USER_LOG_WARN("This feature does not support RTOS platform.");
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
case E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_THERMOMETRY: {
|
||||
returnCode = DjiTest_CameraManagerGetPointThermometryData(mountPosition);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Mounted position %d camera start point thermometry failed, error code: 0x%08X\r\n",
|
||||
mountPosition, returnCode);
|
||||
goto exitCameraModule;
|
||||
}
|
||||
|
||||
returnCode = DjiTest_CameraManagerGetAreaThermometryData(mountPosition);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Mounted position %d camera start area thermometry failed, error code: 0x%08X\r\n",
|
||||
mountPosition, returnCode);
|
||||
goto exitCameraModule;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_GET_LIDAR_RANGING_INFO: {
|
||||
returnCode = DjiTest_CameraManagerGetLidarRangingInfo(mountPosition);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_WARN("Get lidar ranging info failed at position %d, error code: 0x%08X\r\n",
|
||||
mountPosition, returnCode);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_IR_CAMERA_ZOOM_PARAM: {
|
||||
for (uint16_t factor = TEST_CAMERA_MIN_INFRARED_ZOOM_FACTOR;
|
||||
factor <= TEST_CAMERA_MAX_INFRARED_ZOOM_FACTOR;
|
||||
factor = factor * 2) {
|
||||
|
||||
USER_LOG_INFO("Set infrared zoom factor to %d", factor);
|
||||
returnCode = DjiCameraManager_SetInfraredZoomParam(mountPosition, (dji_f32_t) factor);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Mounted position %d camera infrared zoom factor %d rfailed, error code: 0x%08X\r\n",
|
||||
mountPosition, factor, returnCode);
|
||||
goto exitCameraModule;
|
||||
}
|
||||
osalHandler->TaskSleepMs(2000);
|
||||
}
|
||||
break;
|
||||
}
|
||||
default: {
|
||||
USER_LOG_ERROR("There is no valid command input!");
|
||||
break;
|
||||
@ -1160,8 +1271,8 @@ static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_Dj
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
uint16_t downloadCount = 0;
|
||||
nextDownloadFileIndex = 0;
|
||||
|
||||
s_nextDownloadFileIndex = 0;
|
||||
returnCode = DjiCameraManager_RegDownloadFileDataCallback(position, DjiTest_CameraManagerDownloadFileDataCallback);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Register download file data callback failed, error code: 0x%08X.", returnCode);
|
||||
@ -1216,14 +1327,14 @@ static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_Dj
|
||||
|
||||
for (int i = 0; i < downloadCount; ++i) {
|
||||
redownload:
|
||||
if (i != nextDownloadFileIndex) {
|
||||
i = nextDownloadFileIndex;
|
||||
if (i != s_nextDownloadFileIndex) {
|
||||
i = s_nextDownloadFileIndex;
|
||||
}
|
||||
|
||||
returnCode = DjiCameraManager_DownloadFileByIndex(position, s_meidaFileList.fileListInfo[i].fileIndex);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Download media file by index failed, error code: 0x%08X.", returnCode);
|
||||
nextDownloadFileIndex--;
|
||||
s_nextDownloadFileIndex--;
|
||||
goto redownload;
|
||||
}
|
||||
}
|
||||
@ -1252,7 +1363,7 @@ static T_DjiReturnCode DjiTest_CameraManagerDownloadFileDataCallback(T_DjiDownlo
|
||||
if (packetInfo.downloadFileEvent == DJI_DOWNLOAD_FILE_EVENT_START) {
|
||||
for (i = 0; i < s_meidaFileList.totalCount; ++i) {
|
||||
if (s_meidaFileList.fileListInfo[i].fileIndex == packetInfo.fileIndex) {
|
||||
nextDownloadFileIndex = i + 1;
|
||||
s_nextDownloadFileIndex = i + 1;
|
||||
break;
|
||||
}
|
||||
}
|
||||
@ -1260,7 +1371,7 @@ static T_DjiReturnCode DjiTest_CameraManagerDownloadFileDataCallback(T_DjiDownlo
|
||||
|
||||
memset(downloadFileName, 0, sizeof(downloadFileName));
|
||||
snprintf(downloadFileName, sizeof(downloadFileName), "%s", s_meidaFileList.fileListInfo[i].fileName);
|
||||
USER_LOG_INFO("Start download media file, index : %d, next download media file, index: %d", i, nextDownloadFileIndex);
|
||||
USER_LOG_INFO("Start download media file, index : %d, next download media file, index: %d", i, s_nextDownloadFileIndex);
|
||||
s_downloadMediaFile = fopen(downloadFileName, "wb+");
|
||||
if (s_downloadMediaFile == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
@ -1293,4 +1404,118 @@ static T_DjiReturnCode DjiTest_CameraManagerDownloadFileDataCallback(T_DjiDownlo
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiTest_CameraManagerGetPointThermometryData(E_DjiMountPosition position)
|
||||
{
|
||||
T_DjiReturnCode djiStat;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
T_DjiCameraManagerPointThermometryCoordinate pointCoordinate = {0};
|
||||
T_DjiCameraManagerPointThermometryData pointThermometryData = {0};
|
||||
|
||||
USER_LOG_INFO("--> Step 1: Set point thermometry coordinate");
|
||||
|
||||
pointCoordinate.pointX = 0.5;
|
||||
pointCoordinate.pointY = 0.5;
|
||||
djiStat = DjiCameraManager_SetPointThermometryCoordinate(position, pointCoordinate);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Set point thermometry coordinate failed, stat = 0x%08llX", djiStat);
|
||||
return djiStat;
|
||||
}
|
||||
|
||||
USER_LOG_INFO("--> Step 2: Get data of point thermometry");
|
||||
|
||||
for (int i = 0; i < 30; ++i) {
|
||||
osalHandler->TaskSleepMs(1000 / CAMERA_MANAGER_SUBSCRIPTION_FREQ);
|
||||
|
||||
djiStat = DjiCameraManager_GetPointThermometryData(position, &pointThermometryData);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Get data of point thermometry error.");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
}
|
||||
|
||||
USER_LOG_INFO("received camera point thermometry data, point_x = %.2f, point_y = %.2f "
|
||||
"point temperature = %.2f\r\n", pointThermometryData.pointX,
|
||||
pointThermometryData.pointY, pointThermometryData.pointTemperature);
|
||||
}
|
||||
|
||||
return djiStat;
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiTest_CameraManagerGetAreaThermometryData(E_DjiMountPosition position)
|
||||
{
|
||||
T_DjiReturnCode djiStat;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
T_DjiCameraManagerAreaThermometryData areaThermometryData = {0};
|
||||
T_DjiCameraManagerAreaThermometryCoordinate areaCoordinate = {0};
|
||||
|
||||
USER_LOG_INFO("--> Step 1: Set area thermometry coordinate");
|
||||
areaCoordinate.areaTempLtX = 0.2;
|
||||
areaCoordinate.areaTempLtY = 0.2;
|
||||
areaCoordinate.areaTempRbX = 0.8;
|
||||
areaCoordinate.areaTempRbY = 0.8;
|
||||
|
||||
djiStat = DjiCameraManager_SetAreaThermometryCoordinate(position, areaCoordinate);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Set area coordinate failed, stat = 0x%08llX", djiStat);
|
||||
return djiStat;
|
||||
}
|
||||
|
||||
USER_LOG_INFO("--> Step 2: Get data of area thermometry");
|
||||
|
||||
for (int i = 0; i < 30; ++i) {
|
||||
osalHandler->TaskSleepMs(1000 / CAMERA_MANAGER_SUBSCRIPTION_FREQ);
|
||||
|
||||
djiStat = DjiCameraManager_GetAreaThermometryData(position, &areaThermometryData);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Get data of area thermometry error.");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
}
|
||||
|
||||
USER_LOG_INFO("received camera area thermometry data, lt_point_x = %.2f, lt_point_y = %.2f "
|
||||
"rb_point_x = %.2f, rb_point_y = %.2f, area min temperature = %.2f, area max temperature = %.2f, "
|
||||
"area average temperature = %.2f\r\n", areaThermometryData.areaTempLtX,
|
||||
areaThermometryData.areaTempLtY,
|
||||
areaThermometryData.areaTempRbX, areaThermometryData.areaTempRbY, areaThermometryData.areaMinTemp,
|
||||
areaThermometryData.areaMaxTemp, areaThermometryData.areaAveTemp);
|
||||
USER_LOG_INFO("min temperature point_x = %.2f, min temperature point_y = %.2f, max temperature point_x = %.2f, "
|
||||
"max temperature point_y = %.2f\r\n", areaThermometryData.areaMinTempPointX,
|
||||
areaThermometryData.areaMinTempPointY,
|
||||
areaThermometryData.areaMaxTempPointX, areaThermometryData.areaMaxTempPointY);
|
||||
}
|
||||
|
||||
return djiStat;
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiTest_CameraManagerGetLidarRangingInfo(E_DjiMountPosition position)
|
||||
{
|
||||
T_DjiReturnCode returnCode = 0;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
|
||||
T_DjiCameraManagerLaserRangingInfo rangingInfo = {0};
|
||||
|
||||
for (int i = 0; i < 5; i++) {
|
||||
|
||||
osalHandler->TaskSleepMs(1000);
|
||||
|
||||
returnCode = DjiCameraManager_GetLaserRangingInfo(position, &rangingInfo);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Get mounted position %d laser ranging info failed, error code: 0x%08X.",
|
||||
position, returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
USER_LOG_INFO(
|
||||
"Receive lidar range info, lon:%.6f, lat:%.6f, alt:%.1f, dis:%d, enable:%d, exception:%d, x:%d, y:%d",
|
||||
rangingInfo.longitude,
|
||||
rangingInfo.latitude,
|
||||
(float) rangingInfo.altitude / 10,
|
||||
rangingInfo.distance,
|
||||
rangingInfo.enable_lidar,
|
||||
rangingInfo.exception,
|
||||
rangingInfo.screenX,
|
||||
rangingInfo.screenY);
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
|
||||
@ -52,6 +52,10 @@ typedef enum {
|
||||
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_INTERVAL_PHOTO,
|
||||
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_RECORD_VIDEO,
|
||||
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_DOWNLOAD_AND_DELETE_MEDIA_FILE,
|
||||
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_THERMOMETRY,
|
||||
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_GET_LIDAR_RANGING_INFO,
|
||||
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_IR_CAMERA_ZOOM_PARAM,
|
||||
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_INDEX_MAX
|
||||
} E_DjiTestCameraManagerSampleSelect;
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
|
||||
|
||||
@ -391,7 +391,7 @@ static void *UserGimbal_Task(void *arg)
|
||||
NULL);
|
||||
if (djiStat == DJI_ERROR_SUBSCRIPTION_MODULE_CODE_TOPIC_DUPLICATE) {
|
||||
USER_LOG_DEBUG("Subscribe topic quaternion duplicate.");
|
||||
} else {
|
||||
} else if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Subscribe topic quaternion error.");
|
||||
}
|
||||
|
||||
|
||||
@ -152,4 +152,5 @@ out:
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
|
||||
@ -0,0 +1,76 @@
|
||||
{
|
||||
"version": {
|
||||
"major": 1,
|
||||
"minor": 0
|
||||
},
|
||||
"hms_database": {
|
||||
"hms_position_desc": "负载%position_index",
|
||||
"hms_error_code_list": [
|
||||
{
|
||||
"hms_error_code": "0x1E020000",
|
||||
"hms_interface": {
|
||||
"message_title": "HMS测试文案: 我是错误码标题0",
|
||||
"message_content": "HMS测试文案: 我是错误码内容0"
|
||||
},
|
||||
"fpv_interface": {
|
||||
"message_on_the_ground": "HMS测试文案: 我在地面发生了错误0",
|
||||
"is_keep_history_on_the_ground": false,
|
||||
"message_in_the_sky": "HMS测试文案: 我在空中发生了错误0",
|
||||
"is_keep_history_in_the_sky": false
|
||||
}
|
||||
},
|
||||
{
|
||||
"hms_error_code": "0x1E020001",
|
||||
"hms_interface": {
|
||||
"message_title": "HMS测试文案: 我是错误码标题1",
|
||||
"message_content": "HMS测试文案: 我是错误码内容1"
|
||||
},
|
||||
"fpv_interface": {
|
||||
"message_on_the_ground": "HMS测试文案: 我在地面发生了错误1",
|
||||
"is_keep_history_on_the_ground": false,
|
||||
"message_in_the_sky": "HMS测试文案: 我在空中发生了错误1",
|
||||
"is_keep_history_in_the_sky": false
|
||||
}
|
||||
},
|
||||
{
|
||||
"hms_error_code": "0x1E020002",
|
||||
"hms_interface": {
|
||||
"message_title": "HMS测试文案: 我是错误码标题2",
|
||||
"message_content": "HMS测试文案: 我是错误码内容2"
|
||||
},
|
||||
"fpv_interface": {
|
||||
"message_on_the_ground": "HMS测试文案: 我在地面发生了错误2",
|
||||
"is_keep_history_on_the_ground": true,
|
||||
"message_in_the_sky": "HMS测试文案: 我在空中发生了错误2",
|
||||
"is_keep_history_in_the_sky": true
|
||||
}
|
||||
},
|
||||
{
|
||||
"hms_error_code": "0x1E020003",
|
||||
"hms_interface": {
|
||||
"message_title": "HMS测试文案: 我是错误码标题3",
|
||||
"message_content": "HMS测试文案: 我是错误码内容3"
|
||||
},
|
||||
"fpv_interface": {
|
||||
"message_on_the_ground": "HMS测试文案: 我在地面发生了错误3",
|
||||
"is_keep_history_on_the_ground": true,
|
||||
"message_in_the_sky": "HMS测试文案: 我在空中发生了错误3",
|
||||
"is_keep_history_in_the_sky": true
|
||||
}
|
||||
},
|
||||
{
|
||||
"hms_error_code": "0x1E020004",
|
||||
"hms_interface": {
|
||||
"message_title": "HMS测试文案: 我是错误码标题4",
|
||||
"message_content": "HMS测试文案: 我是错误码内容4"
|
||||
},
|
||||
"fpv_interface": {
|
||||
"message_on_the_ground": "HMS测试文案: 我在地面发生了错误4",
|
||||
"is_keep_history_on_the_ground": true,
|
||||
"message_in_the_sky": "HMS测试文案: 我在空中发生了错误4",
|
||||
"is_keep_history_in_the_sky": true
|
||||
}
|
||||
}
|
||||
]
|
||||
}
|
||||
}
|
||||
@ -0,0 +1,76 @@
|
||||
{
|
||||
"version": {
|
||||
"major": 1,
|
||||
"minor": 0
|
||||
},
|
||||
"hms_database": {
|
||||
"hms_position_desc": "Payload %position_index",
|
||||
"hms_error_code_list": [
|
||||
{
|
||||
"hms_error_code": "0x1E020000",
|
||||
"hms_interface": {
|
||||
"message_title": "HMS test text: I am error code Title 0",
|
||||
"message_content": "HMS test text: I am error code Content 0"
|
||||
},
|
||||
"fpv_interface": {
|
||||
"message_on_the_ground": "HMS test text: I got error on the ground 0",
|
||||
"is_keep_history_on_the_ground": false,
|
||||
"message_in_the_sky": "HMS test text: I got error in the sky 0",
|
||||
"is_keep_history_in_the_sky": false
|
||||
}
|
||||
},
|
||||
{
|
||||
"hms_error_code": "0x1E020001",
|
||||
"hms_interface": {
|
||||
"message_title": "HMS test text: I am error code Title 1",
|
||||
"message_content": "HMS test text: I am error code Content 1"
|
||||
},
|
||||
"fpv_interface": {
|
||||
"message_on_the_ground": "HMS test text: I got error on the ground 1",
|
||||
"is_keep_history_on_the_ground": false,
|
||||
"message_in_the_sky": "HMS test text: I got error in the sky 1",
|
||||
"is_keep_history_in_the_sky": false
|
||||
}
|
||||
},
|
||||
{
|
||||
"hms_error_code": "0x1E020002",
|
||||
"hms_interface": {
|
||||
"message_title": "HMS test text: I am error code Title 2",
|
||||
"message_content": "HMS test text: I am error code Content 2"
|
||||
},
|
||||
"fpv_interface": {
|
||||
"message_on_the_ground": "HMS test text: I got error on the ground 2",
|
||||
"is_keep_history_on_the_ground": true,
|
||||
"message_in_the_sky": "HMS test text: I got error in the sky 2",
|
||||
"is_keep_history_in_the_sky": true
|
||||
}
|
||||
},
|
||||
{
|
||||
"hms_error_code": "0x1E020003",
|
||||
"hms_interface": {
|
||||
"message_title": "HMS test text: I am error code Title 3",
|
||||
"message_content": "HMS test text: I am error code Content 3"
|
||||
},
|
||||
"fpv_interface": {
|
||||
"message_on_the_ground": "HMS test text: I got error on the ground 3",
|
||||
"is_keep_history_on_the_ground": true,
|
||||
"message_in_the_sky": "HMS test text: I got error in the sky 3",
|
||||
"is_keep_history_in_the_sky": true
|
||||
}
|
||||
},
|
||||
{
|
||||
"hms_error_code": "0x1E020004",
|
||||
"hms_interface": {
|
||||
"message_title": "HMS test text: I am error code Title 4",
|
||||
"message_content": "HMS test text: I am error code Content 4"
|
||||
},
|
||||
"fpv_interface": {
|
||||
"message_on_the_ground": "HMS test text: I got error on the ground 4",
|
||||
"is_keep_history_on_the_ground": true,
|
||||
"message_in_the_sky": "HMS test text: I got error in the sky 4",
|
||||
"is_keep_history_in_the_sky": true
|
||||
}
|
||||
}
|
||||
]
|
||||
}
|
||||
}
|
||||
@ -0,0 +1,188 @@
|
||||
/* Generated by file2c, do not edit manually */
|
||||
#ifndef __hms_text_config_json_h_included
|
||||
#define __hms_text_config_json_h_included
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
/* Contents of file hms_text_config.json */
|
||||
#define hms_text_config_json_fileName "hms_text_config.json"
|
||||
#define hms_text_config_json_fileSize 2783
|
||||
|
||||
static const uint8_t hms_text_config_json_fileBinaryArray[2783] = {
|
||||
0x7B, 0x0A, 0x20, 0x20, 0x22, 0x76, 0x65, 0x72, 0x73, 0x69, 0x6F, 0x6E, 0x22, 0x3A, 0x20, 0x7B,
|
||||
0x0A, 0x20, 0x20, 0x20, 0x20, 0x22, 0x6D, 0x61, 0x6A, 0x6F, 0x72, 0x22, 0x3A, 0x20, 0x31, 0x2C,
|
||||
0x0A, 0x20, 0x20, 0x20, 0x20, 0x22, 0x6D, 0x69, 0x6E, 0x6F, 0x72, 0x22, 0x3A, 0x20, 0x30, 0x0A,
|
||||
0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x22, 0x68, 0x6D, 0x73, 0x5F, 0x64, 0x61, 0x74, 0x61,
|
||||
0x62, 0x61, 0x73, 0x65, 0x22, 0x3A, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x22, 0x68, 0x6D,
|
||||
0x73, 0x5F, 0x70, 0x6F, 0x73, 0x69, 0x74, 0x69, 0x6F, 0x6E, 0x5F, 0x64, 0x65, 0x73, 0x63, 0x22,
|
||||
0x3A, 0x20, 0x22, 0x50, 0x61, 0x79, 0x6C, 0x6F, 0x61, 0x64, 0x20, 0x25, 0x70, 0x6F, 0x73, 0x69,
|
||||
0x74, 0x69, 0x6F, 0x6E, 0x5F, 0x69, 0x6E, 0x64, 0x65, 0x78, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20,
|
||||
0x20, 0x22, 0x68, 0x6D, 0x73, 0x5F, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x5F, 0x63, 0x6F, 0x64, 0x65,
|
||||
0x5F, 0x6C, 0x69, 0x73, 0x74, 0x22, 0x3A, 0x20, 0x5B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x68, 0x6D, 0x73, 0x5F, 0x65,
|
||||
0x72, 0x72, 0x6F, 0x72, 0x5F, 0x63, 0x6F, 0x64, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x30, 0x78, 0x31,
|
||||
0x45, 0x30, 0x32, 0x30, 0x30, 0x30, 0x30, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x22, 0x68, 0x6D, 0x73, 0x5F, 0x69, 0x6E, 0x74, 0x65, 0x72, 0x66, 0x61, 0x63, 0x65,
|
||||
0x22, 0x3A, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22,
|
||||
0x6D, 0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5F, 0x74, 0x69, 0x74, 0x6C, 0x65, 0x22, 0x3A, 0x20,
|
||||
0x22, 0x48, 0x4D, 0x53, 0x20, 0x74, 0x65, 0x73, 0x74, 0x20, 0x74, 0x65, 0x78, 0x74, 0x3A, 0x20,
|
||||
0x49, 0x20, 0x61, 0x6D, 0x20, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x20, 0x63, 0x6F, 0x64, 0x65, 0x20,
|
||||
0x54, 0x69, 0x74, 0x6C, 0x65, 0x20, 0x30, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x22, 0x6D, 0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5F, 0x63, 0x6F, 0x6E,
|
||||
0x74, 0x65, 0x6E, 0x74, 0x22, 0x3A, 0x20, 0x22, 0x48, 0x4D, 0x53, 0x20, 0x74, 0x65, 0x73, 0x74,
|
||||
0x20, 0x74, 0x65, 0x78, 0x74, 0x3A, 0x20, 0x49, 0x20, 0x61, 0x6D, 0x20, 0x65, 0x72, 0x72, 0x6F,
|
||||
0x72, 0x20, 0x63, 0x6F, 0x64, 0x65, 0x20, 0x43, 0x6F, 0x6E, 0x74, 0x65, 0x6E, 0x74, 0x20, 0x30,
|
||||
0x22, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x66, 0x70, 0x76, 0x5F, 0x69, 0x6E, 0x74, 0x65, 0x72, 0x66,
|
||||
0x61, 0x63, 0x65, 0x22, 0x3A, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x22, 0x6D, 0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5F, 0x6F, 0x6E, 0x5F, 0x74, 0x68,
|
||||
0x65, 0x5F, 0x67, 0x72, 0x6F, 0x75, 0x6E, 0x64, 0x22, 0x3A, 0x20, 0x22, 0x48, 0x4D, 0x53, 0x20,
|
||||
0x74, 0x65, 0x73, 0x74, 0x20, 0x74, 0x65, 0x78, 0x74, 0x3A, 0x20, 0x49, 0x20, 0x67, 0x6F, 0x74,
|
||||
0x20, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x20, 0x6F, 0x6E, 0x20, 0x74, 0x68, 0x65, 0x20, 0x67, 0x72,
|
||||
0x6F, 0x75, 0x6E, 0x64, 0x20, 0x30, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x22, 0x69, 0x73, 0x5F, 0x6B, 0x65, 0x65, 0x70, 0x5F, 0x68, 0x69, 0x73, 0x74,
|
||||
0x6F, 0x72, 0x79, 0x5F, 0x6F, 0x6E, 0x5F, 0x74, 0x68, 0x65, 0x5F, 0x67, 0x72, 0x6F, 0x75, 0x6E,
|
||||
0x64, 0x22, 0x3A, 0x20, 0x66, 0x61, 0x6C, 0x73, 0x65, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x6D, 0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5F, 0x69, 0x6E,
|
||||
0x5F, 0x74, 0x68, 0x65, 0x5F, 0x73, 0x6B, 0x79, 0x22, 0x3A, 0x20, 0x22, 0x48, 0x4D, 0x53, 0x20,
|
||||
0x74, 0x65, 0x73, 0x74, 0x20, 0x74, 0x65, 0x78, 0x74, 0x3A, 0x20, 0x49, 0x20, 0x67, 0x6F, 0x74,
|
||||
0x20, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x20, 0x69, 0x6E, 0x20, 0x74, 0x68, 0x65, 0x20, 0x73, 0x6B,
|
||||
0x79, 0x20, 0x30, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x22, 0x69, 0x73, 0x5F, 0x6B, 0x65, 0x65, 0x70, 0x5F, 0x68, 0x69, 0x73, 0x74, 0x6F, 0x72, 0x79,
|
||||
0x5F, 0x69, 0x6E, 0x5F, 0x74, 0x68, 0x65, 0x5F, 0x73, 0x6B, 0x79, 0x22, 0x3A, 0x20, 0x66, 0x61,
|
||||
0x6C, 0x73, 0x65, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x0A, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7B, 0x0A, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x68, 0x6D, 0x73, 0x5F, 0x65, 0x72, 0x72, 0x6F,
|
||||
0x72, 0x5F, 0x63, 0x6F, 0x64, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x30, 0x78, 0x31, 0x45, 0x30, 0x32,
|
||||
0x30, 0x30, 0x30, 0x31, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22,
|
||||
0x68, 0x6D, 0x73, 0x5F, 0x69, 0x6E, 0x74, 0x65, 0x72, 0x66, 0x61, 0x63, 0x65, 0x22, 0x3A, 0x20,
|
||||
0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x6D, 0x65, 0x73,
|
||||
0x73, 0x61, 0x67, 0x65, 0x5F, 0x74, 0x69, 0x74, 0x6C, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x48, 0x4D,
|
||||
0x53, 0x20, 0x74, 0x65, 0x73, 0x74, 0x20, 0x74, 0x65, 0x78, 0x74, 0x3A, 0x20, 0x49, 0x20, 0x61,
|
||||
0x6D, 0x20, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x20, 0x63, 0x6F, 0x64, 0x65, 0x20, 0x54, 0x69, 0x74,
|
||||
0x6C, 0x65, 0x20, 0x31, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x22, 0x6D, 0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5F, 0x63, 0x6F, 0x6E, 0x74, 0x65, 0x6E,
|
||||
0x74, 0x22, 0x3A, 0x20, 0x22, 0x48, 0x4D, 0x53, 0x20, 0x74, 0x65, 0x73, 0x74, 0x20, 0x74, 0x65,
|
||||
0x78, 0x74, 0x3A, 0x20, 0x49, 0x20, 0x61, 0x6D, 0x20, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x20, 0x63,
|
||||
0x6F, 0x64, 0x65, 0x20, 0x43, 0x6F, 0x6E, 0x74, 0x65, 0x6E, 0x74, 0x20, 0x31, 0x22, 0x0A, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x22, 0x66, 0x70, 0x76, 0x5F, 0x69, 0x6E, 0x74, 0x65, 0x72, 0x66, 0x61, 0x63, 0x65,
|
||||
0x22, 0x3A, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22,
|
||||
0x6D, 0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5F, 0x6F, 0x6E, 0x5F, 0x74, 0x68, 0x65, 0x5F, 0x67,
|
||||
0x72, 0x6F, 0x75, 0x6E, 0x64, 0x22, 0x3A, 0x20, 0x22, 0x48, 0x4D, 0x53, 0x20, 0x74, 0x65, 0x73,
|
||||
0x74, 0x20, 0x74, 0x65, 0x78, 0x74, 0x3A, 0x20, 0x49, 0x20, 0x67, 0x6F, 0x74, 0x20, 0x65, 0x72,
|
||||
0x72, 0x6F, 0x72, 0x20, 0x6F, 0x6E, 0x20, 0x74, 0x68, 0x65, 0x20, 0x67, 0x72, 0x6F, 0x75, 0x6E,
|
||||
0x64, 0x20, 0x31, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x22, 0x69, 0x73, 0x5F, 0x6B, 0x65, 0x65, 0x70, 0x5F, 0x68, 0x69, 0x73, 0x74, 0x6F, 0x72, 0x79,
|
||||
0x5F, 0x6F, 0x6E, 0x5F, 0x74, 0x68, 0x65, 0x5F, 0x67, 0x72, 0x6F, 0x75, 0x6E, 0x64, 0x22, 0x3A,
|
||||
0x20, 0x66, 0x61, 0x6C, 0x73, 0x65, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x22, 0x6D, 0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5F, 0x69, 0x6E, 0x5F, 0x74, 0x68,
|
||||
0x65, 0x5F, 0x73, 0x6B, 0x79, 0x22, 0x3A, 0x20, 0x22, 0x48, 0x4D, 0x53, 0x20, 0x74, 0x65, 0x73,
|
||||
0x74, 0x20, 0x74, 0x65, 0x78, 0x74, 0x3A, 0x20, 0x49, 0x20, 0x67, 0x6F, 0x74, 0x20, 0x65, 0x72,
|
||||
0x72, 0x6F, 0x72, 0x20, 0x69, 0x6E, 0x20, 0x74, 0x68, 0x65, 0x20, 0x73, 0x6B, 0x79, 0x20, 0x31,
|
||||
0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x69, 0x73,
|
||||
0x5F, 0x6B, 0x65, 0x65, 0x70, 0x5F, 0x68, 0x69, 0x73, 0x74, 0x6F, 0x72, 0x79, 0x5F, 0x69, 0x6E,
|
||||
0x5F, 0x74, 0x68, 0x65, 0x5F, 0x73, 0x6B, 0x79, 0x22, 0x3A, 0x20, 0x66, 0x61, 0x6C, 0x73, 0x65,
|
||||
0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x22, 0x68, 0x6D, 0x73, 0x5F, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x5F, 0x63,
|
||||
0x6F, 0x64, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x30, 0x78, 0x31, 0x45, 0x30, 0x32, 0x30, 0x30, 0x30,
|
||||
0x32, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x68, 0x6D, 0x73,
|
||||
0x5F, 0x69, 0x6E, 0x74, 0x65, 0x72, 0x66, 0x61, 0x63, 0x65, 0x22, 0x3A, 0x20, 0x7B, 0x0A, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x6D, 0x65, 0x73, 0x73, 0x61, 0x67,
|
||||
0x65, 0x5F, 0x74, 0x69, 0x74, 0x6C, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x48, 0x4D, 0x53, 0x20, 0x74,
|
||||
0x65, 0x73, 0x74, 0x20, 0x74, 0x65, 0x78, 0x74, 0x3A, 0x20, 0x49, 0x20, 0x61, 0x6D, 0x20, 0x65,
|
||||
0x72, 0x72, 0x6F, 0x72, 0x20, 0x63, 0x6F, 0x64, 0x65, 0x20, 0x54, 0x69, 0x74, 0x6C, 0x65, 0x20,
|
||||
0x32, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x6D,
|
||||
0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5F, 0x63, 0x6F, 0x6E, 0x74, 0x65, 0x6E, 0x74, 0x22, 0x3A,
|
||||
0x20, 0x22, 0x48, 0x4D, 0x53, 0x20, 0x74, 0x65, 0x73, 0x74, 0x20, 0x74, 0x65, 0x78, 0x74, 0x3A,
|
||||
0x20, 0x49, 0x20, 0x61, 0x6D, 0x20, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x20, 0x63, 0x6F, 0x64, 0x65,
|
||||
0x20, 0x43, 0x6F, 0x6E, 0x74, 0x65, 0x6E, 0x74, 0x20, 0x32, 0x22, 0x0A, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22,
|
||||
0x66, 0x70, 0x76, 0x5F, 0x69, 0x6E, 0x74, 0x65, 0x72, 0x66, 0x61, 0x63, 0x65, 0x22, 0x3A, 0x20,
|
||||
0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x6D, 0x65, 0x73,
|
||||
0x73, 0x61, 0x67, 0x65, 0x5F, 0x6F, 0x6E, 0x5F, 0x74, 0x68, 0x65, 0x5F, 0x67, 0x72, 0x6F, 0x75,
|
||||
0x6E, 0x64, 0x22, 0x3A, 0x20, 0x22, 0x48, 0x4D, 0x53, 0x20, 0x74, 0x65, 0x73, 0x74, 0x20, 0x74,
|
||||
0x65, 0x78, 0x74, 0x3A, 0x20, 0x49, 0x20, 0x67, 0x6F, 0x74, 0x20, 0x65, 0x72, 0x72, 0x6F, 0x72,
|
||||
0x20, 0x6F, 0x6E, 0x20, 0x74, 0x68, 0x65, 0x20, 0x67, 0x72, 0x6F, 0x75, 0x6E, 0x64, 0x20, 0x32,
|
||||
0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x69, 0x73,
|
||||
0x5F, 0x6B, 0x65, 0x65, 0x70, 0x5F, 0x68, 0x69, 0x73, 0x74, 0x6F, 0x72, 0x79, 0x5F, 0x6F, 0x6E,
|
||||
0x5F, 0x74, 0x68, 0x65, 0x5F, 0x67, 0x72, 0x6F, 0x75, 0x6E, 0x64, 0x22, 0x3A, 0x20, 0x74, 0x72,
|
||||
0x75, 0x65, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x6D,
|
||||
0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5F, 0x69, 0x6E, 0x5F, 0x74, 0x68, 0x65, 0x5F, 0x73, 0x6B,
|
||||
0x79, 0x22, 0x3A, 0x20, 0x22, 0x48, 0x4D, 0x53, 0x20, 0x74, 0x65, 0x73, 0x74, 0x20, 0x74, 0x65,
|
||||
0x78, 0x74, 0x3A, 0x20, 0x49, 0x20, 0x67, 0x6F, 0x74, 0x20, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x20,
|
||||
0x69, 0x6E, 0x20, 0x74, 0x68, 0x65, 0x20, 0x73, 0x6B, 0x79, 0x20, 0x32, 0x22, 0x2C, 0x0A, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x69, 0x73, 0x5F, 0x6B, 0x65, 0x65,
|
||||
0x70, 0x5F, 0x68, 0x69, 0x73, 0x74, 0x6F, 0x72, 0x79, 0x5F, 0x69, 0x6E, 0x5F, 0x74, 0x68, 0x65,
|
||||
0x5F, 0x73, 0x6B, 0x79, 0x22, 0x3A, 0x20, 0x74, 0x72, 0x75, 0x65, 0x0A, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x7D, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22,
|
||||
0x68, 0x6D, 0x73, 0x5F, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x5F, 0x63, 0x6F, 0x64, 0x65, 0x22, 0x3A,
|
||||
0x20, 0x22, 0x30, 0x78, 0x31, 0x45, 0x30, 0x32, 0x30, 0x30, 0x30, 0x33, 0x22, 0x2C, 0x0A, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x68, 0x6D, 0x73, 0x5F, 0x69, 0x6E, 0x74, 0x65,
|
||||
0x72, 0x66, 0x61, 0x63, 0x65, 0x22, 0x3A, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x22, 0x6D, 0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5F, 0x74, 0x69, 0x74,
|
||||
0x6C, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x48, 0x4D, 0x53, 0x20, 0x74, 0x65, 0x73, 0x74, 0x20, 0x74,
|
||||
0x65, 0x78, 0x74, 0x3A, 0x20, 0x49, 0x20, 0x61, 0x6D, 0x20, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x20,
|
||||
0x63, 0x6F, 0x64, 0x65, 0x20, 0x54, 0x69, 0x74, 0x6C, 0x65, 0x20, 0x33, 0x22, 0x2C, 0x0A, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x6D, 0x65, 0x73, 0x73, 0x61, 0x67,
|
||||
0x65, 0x5F, 0x63, 0x6F, 0x6E, 0x74, 0x65, 0x6E, 0x74, 0x22, 0x3A, 0x20, 0x22, 0x48, 0x4D, 0x53,
|
||||
0x20, 0x74, 0x65, 0x73, 0x74, 0x20, 0x74, 0x65, 0x78, 0x74, 0x3A, 0x20, 0x49, 0x20, 0x61, 0x6D,
|
||||
0x20, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x20, 0x63, 0x6F, 0x64, 0x65, 0x20, 0x43, 0x6F, 0x6E, 0x74,
|
||||
0x65, 0x6E, 0x74, 0x20, 0x33, 0x22, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D,
|
||||
0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x66, 0x70, 0x76, 0x5F, 0x69,
|
||||
0x6E, 0x74, 0x65, 0x72, 0x66, 0x61, 0x63, 0x65, 0x22, 0x3A, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x6D, 0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5F,
|
||||
0x6F, 0x6E, 0x5F, 0x74, 0x68, 0x65, 0x5F, 0x67, 0x72, 0x6F, 0x75, 0x6E, 0x64, 0x22, 0x3A, 0x20,
|
||||
0x22, 0x48, 0x4D, 0x53, 0x20, 0x74, 0x65, 0x73, 0x74, 0x20, 0x74, 0x65, 0x78, 0x74, 0x3A, 0x20,
|
||||
0x49, 0x20, 0x67, 0x6F, 0x74, 0x20, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x20, 0x6F, 0x6E, 0x20, 0x74,
|
||||
0x68, 0x65, 0x20, 0x67, 0x72, 0x6F, 0x75, 0x6E, 0x64, 0x20, 0x33, 0x22, 0x2C, 0x0A, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x69, 0x73, 0x5F, 0x6B, 0x65, 0x65, 0x70,
|
||||
0x5F, 0x68, 0x69, 0x73, 0x74, 0x6F, 0x72, 0x79, 0x5F, 0x6F, 0x6E, 0x5F, 0x74, 0x68, 0x65, 0x5F,
|
||||
0x67, 0x72, 0x6F, 0x75, 0x6E, 0x64, 0x22, 0x3A, 0x20, 0x74, 0x72, 0x75, 0x65, 0x2C, 0x0A, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x6D, 0x65, 0x73, 0x73, 0x61, 0x67,
|
||||
0x65, 0x5F, 0x69, 0x6E, 0x5F, 0x74, 0x68, 0x65, 0x5F, 0x73, 0x6B, 0x79, 0x22, 0x3A, 0x20, 0x22,
|
||||
0x48, 0x4D, 0x53, 0x20, 0x74, 0x65, 0x73, 0x74, 0x20, 0x74, 0x65, 0x78, 0x74, 0x3A, 0x20, 0x49,
|
||||
0x20, 0x67, 0x6F, 0x74, 0x20, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x20, 0x69, 0x6E, 0x20, 0x74, 0x68,
|
||||
0x65, 0x20, 0x73, 0x6B, 0x79, 0x20, 0x33, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x22, 0x69, 0x73, 0x5F, 0x6B, 0x65, 0x65, 0x70, 0x5F, 0x68, 0x69, 0x73,
|
||||
0x74, 0x6F, 0x72, 0x79, 0x5F, 0x69, 0x6E, 0x5F, 0x74, 0x68, 0x65, 0x5F, 0x73, 0x6B, 0x79, 0x22,
|
||||
0x3A, 0x20, 0x74, 0x72, 0x75, 0x65, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D,
|
||||
0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x68, 0x6D, 0x73, 0x5F, 0x65,
|
||||
0x72, 0x72, 0x6F, 0x72, 0x5F, 0x63, 0x6F, 0x64, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x30, 0x78, 0x31,
|
||||
0x45, 0x30, 0x32, 0x30, 0x30, 0x30, 0x34, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x22, 0x68, 0x6D, 0x73, 0x5F, 0x69, 0x6E, 0x74, 0x65, 0x72, 0x66, 0x61, 0x63, 0x65,
|
||||
0x22, 0x3A, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22,
|
||||
0x6D, 0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5F, 0x74, 0x69, 0x74, 0x6C, 0x65, 0x22, 0x3A, 0x20,
|
||||
0x22, 0x48, 0x4D, 0x53, 0x20, 0x74, 0x65, 0x73, 0x74, 0x20, 0x74, 0x65, 0x78, 0x74, 0x3A, 0x20,
|
||||
0x49, 0x20, 0x61, 0x6D, 0x20, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x20, 0x63, 0x6F, 0x64, 0x65, 0x20,
|
||||
0x54, 0x69, 0x74, 0x6C, 0x65, 0x20, 0x34, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x22, 0x6D, 0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5F, 0x63, 0x6F, 0x6E,
|
||||
0x74, 0x65, 0x6E, 0x74, 0x22, 0x3A, 0x20, 0x22, 0x48, 0x4D, 0x53, 0x20, 0x74, 0x65, 0x73, 0x74,
|
||||
0x20, 0x74, 0x65, 0x78, 0x74, 0x3A, 0x20, 0x49, 0x20, 0x61, 0x6D, 0x20, 0x65, 0x72, 0x72, 0x6F,
|
||||
0x72, 0x20, 0x63, 0x6F, 0x64, 0x65, 0x20, 0x43, 0x6F, 0x6E, 0x74, 0x65, 0x6E, 0x74, 0x20, 0x34,
|
||||
0x22, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x66, 0x70, 0x76, 0x5F, 0x69, 0x6E, 0x74, 0x65, 0x72, 0x66,
|
||||
0x61, 0x63, 0x65, 0x22, 0x3A, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x22, 0x6D, 0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5F, 0x6F, 0x6E, 0x5F, 0x74, 0x68,
|
||||
0x65, 0x5F, 0x67, 0x72, 0x6F, 0x75, 0x6E, 0x64, 0x22, 0x3A, 0x20, 0x22, 0x48, 0x4D, 0x53, 0x20,
|
||||
0x74, 0x65, 0x73, 0x74, 0x20, 0x74, 0x65, 0x78, 0x74, 0x3A, 0x20, 0x49, 0x20, 0x67, 0x6F, 0x74,
|
||||
0x20, 0x65, 0x72, 0x72, 0x6F, 0x72, 0x20, 0x6F, 0x6E, 0x20, 0x74, 0x68, 0x65, 0x20, 0x67, 0x72,
|
||||
0x6F, 0x75, 0x6E, 0x64, 0x20, 0x34, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x22, 0x69, 0x73, 0x5F, 0x6B, 0x65, 0x65, 0x70, 0x5F, 0x68, 0x69, 0x73, 0x74,
|
||||
0x6F, 0x72, 0x79, 0x5F, 0x6F, 0x6E, 0x5F, 0x74, 0x68, 0x65, 0x5F, 0x67, 0x72, 0x6F, 0x75, 0x6E,
|
||||
0x64, 0x22, 0x3A, 0x20, 0x74, 0x72, 0x75, 0x65, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x22, 0x6D, 0x65, 0x73, 0x73, 0x61, 0x67, 0x65, 0x5F, 0x69, 0x6E, 0x5F,
|
||||
0x74, 0x68, 0x65, 0x5F, 0x73, 0x6B, 0x79, 0x22, 0x3A, 0x20, 0x22, 0x48, 0x4D, 0x53, 0x20, 0x74,
|
||||
0x65, 0x73, 0x74, 0x20, 0x74, 0x65, 0x78, 0x74, 0x3A, 0x20, 0x49, 0x20, 0x67, 0x6F, 0x74, 0x20,
|
||||
0x65, 0x72, 0x72, 0x6F, 0x72, 0x20, 0x69, 0x6E, 0x20, 0x74, 0x68, 0x65, 0x20, 0x73, 0x6B, 0x79,
|
||||
0x20, 0x34, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22,
|
||||
0x69, 0x73, 0x5F, 0x6B, 0x65, 0x65, 0x70, 0x5F, 0x68, 0x69, 0x73, 0x74, 0x6F, 0x72, 0x79, 0x5F,
|
||||
0x69, 0x6E, 0x5F, 0x74, 0x68, 0x65, 0x5F, 0x73, 0x6B, 0x79, 0x22, 0x3A, 0x20, 0x74, 0x72, 0x75,
|
||||
0x65, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x0A, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x7D, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x5D, 0x0A, 0x20, 0x20, 0x7D, 0x0A, 0x7D
|
||||
};
|
||||
|
||||
#endif /* __hms_text_config_json_h_included */
|
||||
@ -24,25 +24,34 @@
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <widget_interaction_test/test_widget_interaction.h>
|
||||
#include <utils/util_misc.h>
|
||||
#include "test_hms.h"
|
||||
#include "dji_hms.h"
|
||||
#include "dji_hms_info_table.h"
|
||||
#include "dji_logger.h"
|
||||
#include "dji_platform.h"
|
||||
#include "dji_fc_subscription.h"
|
||||
#include "hms_text_c/en/hms_text_config_json.h"
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define MAX_HMS_PRINT_COUNT 150
|
||||
#define MAX_BUFFER_LEN 256
|
||||
#define MIN_HMS_ERROR_LEVEL 0
|
||||
#define MID_HMS_ERROR_LEVEL 3
|
||||
#define MAX_HMS_ERROR_LEVEL 6
|
||||
#define MAX_HMS_PRINT_COUNT (150)
|
||||
#define MAX_BUFFER_LEN (256)
|
||||
#define MIN_HMS_ERROR_LEVEL (0)
|
||||
#define MID_HMS_ERROR_LEVEL (3)
|
||||
#define MAX_HMS_ERROR_LEVEL (6)
|
||||
#define HMS_DIR_PATH_LEN_MAX (256)
|
||||
|
||||
#define DJI_CUSTOM_HMS_CODE_INJECT_ON (0)
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
static const char *oldReplaceAlarmIdStr = "%alarmid";
|
||||
static const char *oldReplaceIndexStr = "%index";
|
||||
static const char *oldReplaceComponentIndexStr = "%component_index";
|
||||
static T_DjiHmsFileBinaryArray s_EnHmsTextConfigFileBinaryArrayList[] = {
|
||||
{hms_text_config_json_fileName, hms_text_config_json_fileSize, hms_text_config_json_fileBinaryArray},
|
||||
};
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
static T_DjiReturnCode DjiTest_HmsInit(void);
|
||||
@ -94,6 +103,75 @@ out:
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
T_DjiReturnCode DjiTest_HmsStartService(void)
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
char curFileDirPath[HMS_DIR_PATH_LEN_MAX];
|
||||
char tempPath[HMS_DIR_PATH_LEN_MAX];
|
||||
#endif
|
||||
|
||||
returnCode = DjiHms_Init();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Hms init error, error code:0x%08llX", returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
//Step 2 : Set hms text Config (Linux environment)
|
||||
returnCode = DjiUserUtil_GetCurrentFileDirPath(__FILE__, HMS_DIR_PATH_LEN_MAX, curFileDirPath);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Get file current path error, stat = 0x%08llX", returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
snprintf(tempPath, HMS_DIR_PATH_LEN_MAX, "%shms_text/en", curFileDirPath);
|
||||
|
||||
//set default hms text config path
|
||||
returnCode = DjiHms_RegDefaultHmsTextConfigByDirPath(tempPath);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Add default hms text config error, stat = 0x%08llX", returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
//set hms text config for English language
|
||||
returnCode = DjiHms_RegHmsTextConfigByDirPath(DJI_MOBILE_APP_LANGUAGE_ENGLISH,
|
||||
tempPath);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Add hms text config error, stat = 0x%08llX", returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
//set hms text config for Chinese language
|
||||
snprintf(tempPath, HMS_DIR_PATH_LEN_MAX, "%shms_text/cn", curFileDirPath);
|
||||
returnCode = DjiHms_RegHmsTextConfigByDirPath(DJI_MOBILE_APP_LANGUAGE_CHINESE,
|
||||
tempPath);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Add hms text config error, stat = 0x%08llX", returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
#else
|
||||
//Step 2 : Set hms text Config (RTOS environment)
|
||||
T_DjiHmsBinaryArrayConfig enHmsTextBinaryArrayConfig = {
|
||||
.binaryArrayCount = sizeof(s_EnHmsTextConfigFileBinaryArrayList) / sizeof(T_DjiHmsFileBinaryArray),
|
||||
.fileBinaryArrayList = s_EnHmsTextConfigFileBinaryArrayList
|
||||
};
|
||||
|
||||
//set default hms text config
|
||||
returnCode = DjiHms_RegDefaultHmsTextConfigByBinaryArray(&enHmsTextBinaryArrayConfig);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Add default hms text config error, stat = 0x%08llX", returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if DJI_CUSTOM_HMS_CODE_INJECT_ON
|
||||
DjiHms_InjectHmsErrorCode(0x1E020000, DJI_HMS_ERROR_LEVEL_FATAL);
|
||||
#endif
|
||||
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
static T_DjiReturnCode DjiTest_HmsInit(void)
|
||||
{
|
||||
@ -134,17 +212,17 @@ static T_DjiReturnCode DjiTest_HmsDeInit(void)
|
||||
|
||||
static T_DjiFcSubscriptionFlightStatus DjiTest_GetValueOfFlightStatus(void)
|
||||
{
|
||||
T_DjiReturnCode djiStat;
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiFcSubscriptionFlightStatus flightStatus;
|
||||
T_DjiDataTimestamp flightStatusTimestamp = {0};
|
||||
|
||||
djiStat = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_STATUS_FLIGHT,
|
||||
(uint8_t *) &flightStatus,
|
||||
sizeof(T_DjiFcSubscriptionFlightStatus),
|
||||
&flightStatusTimestamp);
|
||||
returnCode = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_STATUS_FLIGHT,
|
||||
(uint8_t *) &flightStatus,
|
||||
sizeof(T_DjiFcSubscriptionFlightStatus),
|
||||
&flightStatusTimestamp);
|
||||
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Get value of topic flight status failed, error code:0x%08llX", djiStat);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Get value of topic flight status failed, error code:0x%08llX", returnCode);
|
||||
flightStatus = 0;
|
||||
} else {
|
||||
USER_LOG_DEBUG("Timestamp: millisecond %u microsecond %u.", flightStatusTimestamp.millisecond,
|
||||
@ -184,7 +262,6 @@ static bool DjiTest_ReplaceStr(char *buffer, uint32_t bufferMaxLen, const char *
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
static bool DjiTest_MarchErrCodeInfoTable(T_DjiHmsInfoTable hmsInfoTable)
|
||||
{
|
||||
char alarmIdStr[20] = {0};
|
||||
|
||||
@ -40,6 +40,7 @@ extern "C" {
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
T_DjiReturnCode DjiTest_HmsRunSample(void);
|
||||
T_DjiReturnCode DjiTest_HmsStartService(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
||||
@ -33,8 +33,11 @@
|
||||
#include "time.h"
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define TEST_LIVEVIEW_STREAM_FILE_PATH_STR_MAX_SIZE 256
|
||||
#define TEST_LIVEVIEW_STREAM_STROING_TIME_IN_SECONDS 20
|
||||
#define TEST_LIVEVIEW_STREAM_FILE_PATH_STR_MAX_SIZE 256
|
||||
#define TEST_LIVEVIEW_STREAM_STROING_TIME_IN_SECONDS 20
|
||||
|
||||
#define TEST_LIVEVIEW_STREAM_REQUEST_I_FRAME_ON 1
|
||||
#define TEST_LIVEVIEW_STREAM_REQUEST_I_FRAME_TICK_IN_SECONDS 5
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
|
||||
@ -109,15 +112,25 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition)
|
||||
|
||||
for (int i = 0; i < TEST_LIVEVIEW_STREAM_STROING_TIME_IN_SECONDS; ++i) {
|
||||
USER_LOG_INFO("Storing camera h264 stream, second: %d.", i + 1);
|
||||
#if TEST_LIVEVIEW_STREAM_REQUEST_I_FRAME_ON
|
||||
if (i % TEST_LIVEVIEW_STREAM_REQUEST_I_FRAME_TICK_IN_SECONDS == 0) {
|
||||
returnCode = DjiLiveview_RequestIntraframeFrameData((E_DjiLiveViewCameraPosition) mountPosition,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_DEFAULT);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Request stream I frame of payload %d failed, error code: 0x%08X", mountPosition,
|
||||
returnCode);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
osalHandler->TaskSleepMs(1000);
|
||||
}
|
||||
|
||||
USER_LOG_INFO("--> Step 3: Stop h264 stream of the fpv and selected payload\r\n");
|
||||
DjiTest_WidgetLogAppend("--> Step 3: Stop h264 stream of the fpv and selected payload");
|
||||
if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3E) {
|
||||
//TODO: how to use on M3E
|
||||
|
||||
} else if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3T) {
|
||||
//TODO: how to use on M3T
|
||||
|
||||
} else {
|
||||
returnCode = DjiLiveview_StopH264Stream(DJI_LIVEVIEW_CAMERA_POSITION_FPV, DJI_LIVEVIEW_CAMERA_SOURCE_DEFAULT);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -157,7 +170,7 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition)
|
||||
}
|
||||
|
||||
returnCode = DjiLiveview_StopH264Stream((E_DjiLiveViewCameraPosition) mountPosition,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_DEFAULT);
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M3T_IR);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Request to stop h264 of payload %d failed, error code: 0x%08X", mountPosition, returnCode);
|
||||
goto out;
|
||||
|
||||
@ -39,7 +39,8 @@
|
||||
static T_DjiWaypointV3MissionState s_lastWaypointV3MissionState = {0};
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
static T_DjiReturnCode DjiTest_WaypointV3StateCallback(T_DjiWaypointV3MissionState missionState);
|
||||
static T_DjiReturnCode DjiTest_WaypointV3MissionStateCallback(T_DjiWaypointV3MissionState missionState);
|
||||
static T_DjiReturnCode DjiTest_WaypointV3ActionStateCallback(T_DjiWaypointV3ActionState actionState);
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
T_DjiReturnCode DjiTest_WaypointV3RunSample(void)
|
||||
@ -47,7 +48,7 @@ T_DjiReturnCode DjiTest_WaypointV3RunSample(void)
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
FILE *kmzFile;
|
||||
FILE *kmzFile = NULL;
|
||||
uint32_t kmzFileSize = 0;
|
||||
uint8_t *kmzFileBuf;
|
||||
uint16_t readLen;
|
||||
@ -60,12 +61,18 @@ T_DjiReturnCode DjiTest_WaypointV3RunSample(void)
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
returnCode = DjiWaypointV3_RegMissionStateCallback(DjiTest_WaypointV3StateCallback);
|
||||
returnCode = DjiWaypointV3_RegMissionStateCallback(DjiTest_WaypointV3MissionStateCallback);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Register waypoint v3 state callback failed.");
|
||||
goto out;
|
||||
}
|
||||
|
||||
returnCode = DjiWaypointV3_RegActionStateCallback(DjiTest_WaypointV3ActionStateCallback);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Register waypoint v3 action state callback failed.");
|
||||
goto out;
|
||||
}
|
||||
|
||||
returnCode = DjiUserUtil_GetCurrentFileDirPath(__FILE__, DJI_TEST_WAYPOINT_V3_KMZ_FILE_PATH_LEN_MAX,
|
||||
curFileDirPath);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -113,8 +120,8 @@ T_DjiReturnCode DjiTest_WaypointV3RunSample(void)
|
||||
returnCode = DjiWaypointV3_UploadKmzFile(waypoint_v3_test_file_kmz_fileBinaryArray,
|
||||
waypoint_v3_test_file_kmz_fileSize);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Upload kmz file failed.");
|
||||
goto out;
|
||||
USER_LOG_ERROR("Upload kmz file binary array failed.");
|
||||
return returnCode;
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -125,14 +132,24 @@ T_DjiReturnCode DjiTest_WaypointV3RunSample(void)
|
||||
goto out;
|
||||
}
|
||||
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
fclose(kmzFile);
|
||||
#endif
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
|
||||
out:
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
if (kmzFile != NULL) {
|
||||
fclose(kmzFile);
|
||||
}
|
||||
#endif
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
static T_DjiReturnCode DjiTest_WaypointV3StateCallback(T_DjiWaypointV3MissionState missionState)
|
||||
static T_DjiReturnCode DjiTest_WaypointV3MissionStateCallback(T_DjiWaypointV3MissionState missionState)
|
||||
{
|
||||
if (s_lastWaypointV3MissionState.state == missionState.state
|
||||
&& s_lastWaypointV3MissionState.currentWaypointIndex == missionState.currentWaypointIndex
|
||||
@ -147,4 +164,16 @@ static T_DjiReturnCode DjiTest_WaypointV3StateCallback(T_DjiWaypointV3MissionSta
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiTest_WaypointV3ActionStateCallback(T_DjiWaypointV3ActionState actionState)
|
||||
{
|
||||
USER_LOG_INFO(
|
||||
"Waypoint v3 action state: %d, current waypoint index: %d, wayLine id: %d, action group: %d, action id: %d",
|
||||
actionState.state,
|
||||
actionState.currentWaypointIndex, actionState.wayLineId,
|
||||
actionState.actionGroupId, actionState.actionId);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
|
||||
Binary file not shown.
@ -6,209 +6,250 @@
|
||||
|
||||
/* Contents of file waypoint_v3_test_file.kmz */
|
||||
#define waypoint_v3_test_file_kmz_fileName "waypoint_v3_test_file.kmz"
|
||||
#define waypoint_v3_test_file_kmz_fileSize 3186
|
||||
#define waypoint_v3_test_file_kmz_fileSize 3856
|
||||
|
||||
static const uint8_t waypoint_v3_test_file_kmz_fileBinaryArray[3186] = {
|
||||
0x50, 0x4B, 0x03, 0x04, 0x14, 0x00, 0x08, 0x08, 0x08, 0x00, 0x22, 0x6D, 0x34, 0x55, 0x00, 0x00,
|
||||
static const uint8_t waypoint_v3_test_file_kmz_fileBinaryArray[3856] = {
|
||||
0x50, 0x4B, 0x03, 0x04, 0x14, 0x00, 0x08, 0x08, 0x08, 0x00, 0x8A, 0x81, 0x3E, 0x56, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x11, 0x00, 0x00, 0x00, 0x77, 0x70,
|
||||
0x6D, 0x7A, 0x2F, 0x74, 0x65, 0x6D, 0x70, 0x6C, 0x61, 0x74, 0x65, 0x2E, 0x6B, 0x6D, 0x6C, 0xED,
|
||||
0x5B, 0x4D, 0x8F, 0xDB, 0x36, 0x10, 0xBD, 0xE7, 0x57, 0x08, 0x3E, 0xB5, 0x40, 0x6A, 0x53, 0xDF,
|
||||
0x52, 0xE0, 0x38, 0xD8, 0x6E, 0x3E, 0x76, 0x91, 0x4D, 0x63, 0xC4, 0x4E, 0xF7, 0x58, 0x30, 0x32,
|
||||
0x6D, 0xB3, 0x2B, 0x91, 0x86, 0x44, 0xAD, 0xD7, 0x3D, 0x05, 0x28, 0x52, 0xB4, 0x40, 0x4E, 0x2D,
|
||||
0x8A, 0x1E, 0x8A, 0x1E, 0x52, 0xA0, 0x40, 0x4F, 0xBD, 0x34, 0xC7, 0xB4, 0xFF, 0x66, 0x83, 0xF4,
|
||||
0x5F, 0x94, 0x92, 0x25, 0x59, 0x94, 0xE8, 0x4D, 0x10, 0x05, 0xD8, 0xAC, 0x6D, 0x9F, 0x2C, 0xCE,
|
||||
0x7B, 0x43, 0xCD, 0xCC, 0x23, 0x25, 0x0F, 0xE1, 0xEE, 0xAD, 0xB3, 0xC0, 0x57, 0x4E, 0x51, 0x18,
|
||||
0x61, 0x4A, 0x6E, 0xB6, 0xD4, 0x36, 0x68, 0x29, 0x88, 0x78, 0x74, 0x84, 0xC9, 0xE4, 0x66, 0xEB,
|
||||
0xF1, 0xF0, 0xEE, 0x67, 0x4E, 0xEB, 0x56, 0xEF, 0x5A, 0xF7, 0x84, 0xA3, 0x38, 0x92, 0x44, 0x37,
|
||||
0x5B, 0x53, 0xC6, 0x66, 0x37, 0x3A, 0x9D, 0xF9, 0x7C, 0xDE, 0xA6, 0x33, 0x44, 0x26, 0x38, 0x6A,
|
||||
0x13, 0xC4, 0x3A, 0x1C, 0xD1, 0xD1, 0xDA, 0x5A, 0x6B, 0x09, 0xBB, 0x31, 0x9F, 0x05, 0xBE, 0x80,
|
||||
0x1D, 0x7D, 0x8D, 0xDB, 0x1E, 0x0D, 0x3A, 0xDC, 0xF0, 0x4D, 0x87, 0xCF, 0xD3, 0x56, 0x5B, 0xBD,
|
||||
0x6B, 0x8A, 0xD2, 0xBD, 0x4D, 0xBD, 0x38, 0x40, 0x84, 0x25, 0x17, 0xFC, 0x32, 0xE1, 0xDD, 0xF0,
|
||||
0x42, 0x04, 0x19, 0x1A, 0xE2, 0x00, 0xF5, 0x54, 0xCB, 0xD2, 0x2D, 0x53, 0xD3, 0x55, 0x4B, 0x07,
|
||||
0x66, 0xB7, 0x53, 0x35, 0x97, 0x48, 0xF1, 0x6C, 0x54, 0x21, 0x19, 0x86, 0x6B, 0x59, 0x76, 0x46,
|
||||
0x2A, 0x99, 0x4B, 0xA4, 0x00, 0x47, 0x49, 0xE4, 0xFB, 0x94, 0x8C, 0xF1, 0x64, 0x69, 0xC8, 0x4D,
|
||||
0x63, 0x7F, 0x31, 0xA4, 0xC7, 0x70, 0xE1, 0x63, 0x82, 0x1E, 0xD0, 0x11, 0xEA, 0x45, 0x70, 0x8C,
|
||||
0xFC, 0x45, 0xE6, 0xAE, 0x66, 0x15, 0xB9, 0x98, 0xE0, 0x68, 0xBA, 0xE7, 0x31, 0xEE, 0xBB, 0x37,
|
||||
0xA1, 0x07, 0x34, 0x40, 0x39, 0xAF, 0x6C, 0x11, 0x38, 0xE8, 0x0C, 0xB3, 0x87, 0xE4, 0xD1, 0xFE,
|
||||
0x11, 0x8D, 0x58, 0x0F, 0x9D, 0x21, 0x2F, 0x66, 0x28, 0xF9, 0xBE, 0xC4, 0x66, 0x74, 0x01, 0x54,
|
||||
0xA1, 0xA7, 0x8C, 0xA5, 0xA9, 0x98, 0xF9, 0x73, 0xE8, 0x9D, 0x14, 0xD4, 0x3A, 0x40, 0xF0, 0xC0,
|
||||
0xE0, 0x09, 0x7A, 0x38, 0x1E, 0x0F, 0x38, 0x2C, 0xC4, 0x6C, 0x71, 0x80, 0xF0, 0x64, 0xCA, 0x7A,
|
||||
0x1A, 0xC8, 0xF8, 0x72, 0xB3, 0xE0, 0x61, 0xE2, 0xD3, 0x27, 0xD0, 0x1F, 0x86, 0x90, 0x44, 0x38,
|
||||
0xF1, 0x0F, 0xFD, 0xC1, 0x0C, 0xA1, 0x51, 0x2F, 0x2F, 0xDC, 0x3A, 0xBB, 0xE0, 0x64, 0x14, 0x52,
|
||||
0x82, 0x0E, 0xC9, 0x98, 0xE6, 0xC3, 0x82, 0xE1, 0x0E, 0x89, 0x83, 0x2F, 0xA1, 0x1F, 0xA3, 0x9E,
|
||||
0x9D, 0x57, 0xB6, 0x32, 0x2E, 0x63, 0x0D, 0xE2, 0x27, 0x2B, 0x00, 0x28, 0xF3, 0x04, 0x4B, 0x7E,
|
||||
0x1F, 0x1D, 0xF9, 0x8D, 0x2C, 0x1D, 0xCE, 0x78, 0xD1, 0x29, 0x1C, 0xC9, 0xEE, 0x30, 0x33, 0xAD,
|
||||
0x1C, 0x5A, 0x56, 0xE6, 0xAB, 0x66, 0x91, 0x33, 0xA5, 0xF7, 0x29, 0xB3, 0xC9, 0xE9, 0x7D, 0xBA,
|
||||
0xCC, 0xEB, 0x21, 0x19, 0xA1, 0xB3, 0x2A, 0x5F, 0x34, 0x8A, 0xA1, 0x4A, 0x62, 0x7A, 0x8F, 0x60,
|
||||
0x4D, 0x53, 0x37, 0x2E, 0x31, 0x5E, 0xED, 0x1D, 0xE2, 0x2D, 0x76, 0x98, 0x38, 0x62, 0x34, 0xE8,
|
||||
0x2F, 0x91, 0x5F, 0x40, 0xBE, 0x29, 0xF4, 0x07, 0xB7, 0xEF, 0x7F, 0xB5, 0xD7, 0xEF, 0xEF, 0x1D,
|
||||
0x1D, 0xEE, 0x0D, 0xF2, 0x8D, 0xA6, 0x86, 0xAA, 0xB8, 0x19, 0x53, 0x0F, 0xFA, 0x47, 0x7C, 0x13,
|
||||
0x64, 0xD3, 0xE2, 0xF6, 0xCB, 0x63, 0x15, 0x78, 0x84, 0x48, 0x44, 0xC3, 0x83, 0x02, 0x9A, 0x5F,
|
||||
0x4B, 0x61, 0xC7, 0x15, 0xD8, 0x71, 0x15, 0x86, 0x03, 0x38, 0x41, 0x2B, 0x67, 0xD9, 0xA5, 0x0C,
|
||||
0x74, 0x2C, 0x82, 0x6A, 0x9E, 0x02, 0x4C, 0x06, 0x53, 0x4A, 0xD9, 0x21, 0x61, 0x28, 0x3C, 0x85,
|
||||
0x7E, 0x01, 0xAF, 0x19, 0x2E, 0x4A, 0xE3, 0x72, 0x4F, 0x11, 0xA5, 0x22, 0x02, 0x97, 0x88, 0xE1,
|
||||
0x62, 0xC6, 0xB7, 0x68, 0x21, 0xC5, 0x25, 0xC3, 0x85, 0xD4, 0xB4, 0x06, 0xAF, 0x9F, 0xFF, 0xF0,
|
||||
0xDF, 0x8F, 0x7F, 0x49, 0xF8, 0x62, 0x85, 0x64, 0xFC, 0x07, 0x98, 0xF4, 0x61, 0x08, 0x2B, 0x82,
|
||||
0x5B, 0x8F, 0xB8, 0xD8, 0x19, 0x3C, 0x7B, 0x9B, 0x33, 0x01, 0x71, 0xA1, 0x33, 0x71, 0xC9, 0xD6,
|
||||
0x2D, 0xAB, 0xC4, 0x4B, 0xA4, 0x29, 0xCB, 0x7C, 0xD3, 0x02, 0x19, 0xEF, 0x5F, 0xA0, 0xF3, 0xEF,
|
||||
0x7F, 0x79, 0xF3, 0xE2, 0xCF, 0x8D, 0x2C, 0x90, 0x4C, 0xB6, 0x97, 0x54, 0x20, 0xAD, 0x41, 0x81,
|
||||
0x5E, 0x3D, 0x3D, 0x7F, 0xF6, 0xF7, 0x46, 0x16, 0x48, 0x96, 0x95, 0x4B, 0x2A, 0x90, 0xFE, 0xFE,
|
||||
0x05, 0x7A, 0xF3, 0xFC, 0xDB, 0xF3, 0x5F, 0x5F, 0xBE, 0xFE, 0xED, 0xC5, 0x07, 0xA8, 0x91, 0x0A,
|
||||
0x3E, 0xBE, 0x2A, 0xC9, 0x52, 0x73, 0x49, 0x55, 0x6A, 0xFC, 0x20, 0x52, 0x64, 0x3B, 0xE5, 0xD5,
|
||||
0x5F, 0x48, 0xB2, 0xA8, 0xAE, 0xF0, 0x42, 0x52, 0xCC, 0x0D, 0x5D, 0x4A, 0xB2, 0xB8, 0x2E, 0xA9,
|
||||
0x4E, 0xB2, 0x5B, 0x79, 0xD7, 0xA5, 0xF4, 0xF3, 0xCB, 0xF3, 0x7F, 0x7E, 0x3F, 0x7F, 0xFA, 0xEA,
|
||||
0xCD, 0xBF, 0x3F, 0x9D, 0x3F, 0xFB, 0xE3, 0xF5, 0x8B, 0xEF, 0x14, 0x6B, 0x23, 0x97, 0x95, 0x2C,
|
||||
0xAA, 0xAB, 0xF7, 0x02, 0xF1, 0x98, 0xF8, 0xD4, 0x3B, 0x51, 0xC6, 0x7E, 0xD2, 0x03, 0x50, 0x3C,
|
||||
0x4A, 0x58, 0x48, 0x7D, 0x25, 0x44, 0x11, 0x0B, 0x71, 0x8A, 0x8A, 0x94, 0x4F, 0xF8, 0x4F, 0x7B,
|
||||
0x0F, 0x43, 0x5F, 0x81, 0x8C, 0x21, 0x92, 0x8C, 0x7D, 0xBA, 0x91, 0x05, 0xB5, 0x3F, 0x9E, 0x82,
|
||||
0x36, 0x78, 0x65, 0xEF, 0xFB, 0x08, 0x46, 0x48, 0x19, 0x20, 0x1F, 0x79, 0x4C, 0xC9, 0x26, 0x57,
|
||||
0xD2, 0x38, 0x36, 0xB2, 0x6A, 0xCE, 0x06, 0x56, 0x6D, 0x00, 0x83, 0x99, 0x8F, 0x36, 0xB2, 0x5C,
|
||||
0xEE, 0xC7, 0x53, 0xAE, 0x06, 0xEF, 0x8B, 0x8F, 0x62, 0xB2, 0x91, 0xD5, 0x51, 0x3F, 0x58, 0xDB,
|
||||
0x62, 0x5D, 0x3B, 0xB2, 0x68, 0x47, 0xD5, 0xBA, 0xF5, 0xDD, 0xBB, 0xD4, 0x1F, 0xA1, 0xB0, 0xD2,
|
||||
0xC9, 0x46, 0x7C, 0x25, 0x24, 0xDD, 0xFE, 0xA4, 0x2E, 0x73, 0xB8, 0x98, 0x51, 0x4C, 0x58, 0xDE,
|
||||
0xC6, 0x2E, 0xDB, 0xA4, 0xAC, 0xC3, 0x51, 0x91, 0x96, 0xD2, 0x90, 0x00, 0x9D, 0x2F, 0x1B, 0xFF,
|
||||
0xFB, 0x94, 0x86, 0x23, 0x4C, 0x38, 0x60, 0xB0, 0x88, 0xD2, 0x9C, 0xD5, 0x74, 0x56, 0x20, 0xD2,
|
||||
0x43, 0x82, 0xE3, 0x7B, 0x03, 0xA7, 0x58, 0xEF, 0xA2, 0xA9, 0x42, 0x9C, 0xA6, 0xED, 0xF5, 0xD4,
|
||||
0x12, 0x22, 0x7E, 0x0B, 0xF8, 0x14, 0x0D, 0xE9, 0x80, 0xC1, 0x90, 0xF5, 0x4B, 0xC1, 0x94, 0x50,
|
||||
0xD5, 0x0E, 0x69, 0xD6, 0xFD, 0xC4, 0x64, 0x92, 0x46, 0x7A, 0xAF, 0x9F, 0x37, 0x35, 0xAB, 0x16,
|
||||
0x31, 0xF5, 0x6F, 0x8D, 0x6C, 0xE9, 0x1E, 0xC6, 0x8C, 0xDE, 0x4D, 0x9F, 0xFE, 0x62, 0x87, 0xBF,
|
||||
0x3A, 0x2E, 0x39, 0x1E, 0xC8, 0x0E, 0x0E, 0x56, 0xEF, 0xD2, 0xC2, 0xB0, 0x40, 0xF0, 0xA0, 0x8F,
|
||||
0x97, 0xDE, 0xEE, 0x10, 0xF8, 0xC4, 0x2F, 0xC9, 0xB5, 0x6A, 0x10, 0xE7, 0xC1, 0x01, 0x77, 0xD8,
|
||||
0xC7, 0xCC, 0x9B, 0xA6, 0xA9, 0x09, 0x20, 0x89, 0xA1, 0x9F, 0xCF, 0x56, 0x31, 0x4A, 0xEE, 0xF0,
|
||||
0x38, 0x53, 0xCC, 0x01, 0x82, 0xC9, 0x39, 0x98, 0xB4, 0xB0, 0x73, 0x11, 0x93, 0xBA, 0x1A, 0x53,
|
||||
0xDF, 0xA7, 0xF3, 0xEC, 0x50, 0x68, 0x95, 0xCF, 0x1A, 0xEE, 0x62, 0x57, 0x7B, 0x64, 0x52, 0x8A,
|
||||
0x54, 0x6A, 0x5C, 0xE3, 0x80, 0x2B, 0x23, 0x15, 0x47, 0x0F, 0xB4, 0x41, 0xFA, 0xB9, 0x5E, 0xFB,
|
||||
0x52, 0xF1, 0x5A, 0x30, 0x44, 0x11, 0xBC, 0x3D, 0x0D, 0xB2, 0x74, 0x0D, 0xE3, 0x90, 0xA4, 0xF1,
|
||||
0x31, 0x9A, 0x3A, 0xDD, 0x23, 0xA3, 0x01, 0xA3, 0xB3, 0x63, 0xCC, 0xA6, 0xB7, 0x71, 0x94, 0xBC,
|
||||
0x24, 0x62, 0x12, 0x63, 0xB6, 0xD8, 0x8F, 0xC3, 0x53, 0xC8, 0xE2, 0x10, 0x49, 0x67, 0x2B, 0xBC,
|
||||
0x48, 0x66, 0x7A, 0x1C, 0xA1, 0x01, 0x0B, 0x61, 0x52, 0xF7, 0x23, 0x9E, 0xE2, 0x62, 0x2F, 0x96,
|
||||
0x5B, 0x73, 0x07, 0x7D, 0x1F, 0x7A, 0x28, 0x80, 0xE1, 0x49, 0x29, 0x6F, 0x42, 0xD4, 0xE9, 0xC8,
|
||||
0x6A, 0x39, 0x46, 0xE5, 0x71, 0x45, 0x51, 0x55, 0xBD, 0xED, 0xEA, 0x36, 0xD0, 0x4C, 0xC3, 0x35,
|
||||
0x00, 0xB0, 0xAF, 0x6B, 0x5A, 0xDB, 0xB4, 0x5D, 0xCB, 0xB1, 0x55, 0x5D, 0x35, 0x1D, 0xC3, 0x29,
|
||||
0x7B, 0xE9, 0x48, 0xDD, 0x74, 0x3B, 0x95, 0xF9, 0xB2, 0xDE, 0xBC, 0xD0, 0xF3, 0xC5, 0xB2, 0x73,
|
||||
0x0A, 0xE4, 0xFB, 0x78, 0x16, 0x51, 0x3C, 0xAA, 0xAD, 0x9A, 0xAA, 0x45, 0xBA, 0x7F, 0x94, 0xF0,
|
||||
0x53, 0x29, 0x2C, 0x8E, 0xD0, 0x3D, 0x61, 0x55, 0xE6, 0xA7, 0xA5, 0x95, 0xF1, 0x75, 0xB4, 0xE5,
|
||||
0x2A, 0xAF, 0xB1, 0x84, 0xC5, 0x2F, 0x99, 0xAB, 0x24, 0x28, 0xC9, 0x8C, 0xEB, 0x57, 0x5D, 0x01,
|
||||
0x4A, 0x54, 0xB2, 0x86, 0xBF, 0x32, 0xD5, 0xC9, 0x82, 0x3E, 0xC0, 0x8A, 0x29, 0xD5, 0x4D, 0xA7,
|
||||
0x26, 0x9C, 0x0F, 0x23, 0x25, 0xCB, 0x35, 0x5D, 0x9B, 0x7F, 0x4C, 0x23, 0x95, 0x92, 0x03, 0x5C,
|
||||
0x1D, 0xE8, 0x8E, 0x69, 0x58, 0x86, 0xD1, 0x50, 0x4A, 0xEA, 0x4E, 0x4A, 0xDB, 0x25, 0x25, 0x5B,
|
||||
0x77, 0x1C, 0x43, 0xB3, 0x55, 0xC7, 0x2E, 0xA4, 0x64, 0x3A, 0x9A, 0x6A, 0x58, 0x5A, 0xD3, 0x5D,
|
||||
0x49, 0xDB, 0x49, 0x69, 0xCB, 0xA4, 0x64, 0x00, 0xD5, 0x05, 0xC0, 0x70, 0xF2, 0x07, 0x5C, 0xF2,
|
||||
0xC4, 0xB3, 0x0C, 0x0B, 0x80, 0xA6, 0x52, 0xD2, 0x77, 0x52, 0xDA, 0x32, 0x29, 0x39, 0xB6, 0x06,
|
||||
0x2C, 0x53, 0xB7, 0xAC, 0x5C, 0x4A, 0x1A, 0xD0, 0xB9, 0x8E, 0x34, 0x53, 0x6D, 0x28, 0x25, 0x63,
|
||||
0x27, 0xA5, 0x2D, 0x93, 0x92, 0xED, 0x02, 0xCD, 0x76, 0xF4, 0xFC, 0xF1, 0x66, 0xAA, 0x5C, 0x4A,
|
||||
0x06, 0x7F, 0x13, 0x6F, 0x28, 0x24, 0x73, 0x27, 0xA4, 0xED, 0x12, 0x92, 0xA3, 0xDB, 0x1A, 0x57,
|
||||
0x8F, 0x69, 0x16, 0x4A, 0xD2, 0x1D, 0x1B, 0x38, 0xB6, 0x61, 0x37, 0x54, 0x92, 0xB5, 0x53, 0xD2,
|
||||
0x96, 0x29, 0xC9, 0x50, 0x81, 0xA9, 0xB9, 0x86, 0x6E, 0x64, 0x4F, 0x37, 0x07, 0x68, 0x9A, 0x0B,
|
||||
0xB8, 0xBC, 0xB4, 0x86, 0x52, 0xB2, 0x77, 0x52, 0xDA, 0x32, 0x29, 0xB9, 0x86, 0xA5, 0x03, 0x0B,
|
||||
0x38, 0x6A, 0x2E, 0x25, 0xCD, 0xD6, 0x55, 0x5B, 0xD7, 0xD4, 0xA6, 0xBB, 0x92, 0xB3, 0x93, 0xD2,
|
||||
0x96, 0x49, 0xC9, 0x71, 0xB8, 0x90, 0xF8, 0xF3, 0xAD, 0x68, 0x2A, 0x59, 0x2E, 0x30, 0xF8, 0x6F,
|
||||
0xBA, 0xA6, 0x3D, 0x25, 0x77, 0xA7, 0xA4, 0xAB, 0xA1, 0xA4, 0x6E, 0x67, 0x75, 0x14, 0xD6, 0xED,
|
||||
0xAC, 0xFE, 0x56, 0xD3, 0x4D, 0xFE, 0x9A, 0xD3, 0xBB, 0xF6, 0x3F, 0x50, 0x4B, 0x07, 0x08, 0x50,
|
||||
0x7D, 0x0A, 0x8A, 0xCC, 0x05, 0x00, 0x00, 0xEA, 0x33, 0x00, 0x00, 0x50, 0x4B, 0x03, 0x04, 0x14,
|
||||
0x00, 0x08, 0x08, 0x08, 0x00, 0x22, 0x6D, 0x34, 0x55, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, 0x77, 0x70, 0x6D, 0x7A, 0x2F, 0x77, 0x61,
|
||||
0x79, 0x6C, 0x69, 0x6E, 0x65, 0x73, 0x2E, 0x77, 0x70, 0x6D, 0x6C, 0xED, 0x9B, 0x4D, 0x6F, 0xDB,
|
||||
0x36, 0x18, 0xC7, 0xEF, 0xFD, 0x14, 0x82, 0x4F, 0x1B, 0xD0, 0xD9, 0x14, 0xF5, 0x46, 0x15, 0xAE,
|
||||
0x8B, 0xAC, 0x69, 0x91, 0xA0, 0xE9, 0x6A, 0xD4, 0xE9, 0x72, 0x1C, 0x18, 0x99, 0x76, 0xB8, 0xC8,
|
||||
0xA4, 0x21, 0x51, 0x79, 0xD9, 0xA9, 0xC0, 0xD0, 0x61, 0x03, 0x7A, 0xDA, 0x30, 0xEC, 0x30, 0xEC,
|
||||
0xD0, 0x01, 0x03, 0x76, 0xDA, 0x65, 0x3D, 0x76, 0xFB, 0x36, 0x29, 0xB2, 0x6F, 0x31, 0xCA, 0x2F,
|
||||
0xB2, 0x28, 0x33, 0x2F, 0xA8, 0x0A, 0xA7, 0x35, 0x98, 0x93, 0xC5, 0xE7, 0xFF, 0x3C, 0x24, 0x9F,
|
||||
0x87, 0x3F, 0x89, 0xA6, 0xE2, 0xF6, 0xBD, 0x93, 0x51, 0x6C, 0x1D, 0x91, 0x24, 0xA5, 0x9C, 0xDD,
|
||||
0x6D, 0xD8, 0x4D, 0xD0, 0xB0, 0x08, 0x8B, 0x78, 0x9F, 0xB2, 0xE1, 0xDD, 0xC6, 0xB3, 0xDD, 0x87,
|
||||
0x9F, 0xA1, 0xC6, 0xBD, 0xCE, 0xAD, 0xF6, 0xA1, 0x54, 0x49, 0x25, 0x4B, 0xEF, 0x36, 0x0E, 0x84,
|
||||
0x18, 0xDF, 0x69, 0xB5, 0x8E, 0x8F, 0x8F, 0x9B, 0x7C, 0x4C, 0xD8, 0x90, 0xA6, 0x4D, 0x46, 0x44,
|
||||
0x4B, 0x2A, 0x5A, 0xB0, 0x09, 0x1B, 0x53, 0xD9, 0x9D, 0xE3, 0xF1, 0x28, 0x56, 0xB4, 0xFD, 0xAF,
|
||||
0x69, 0x33, 0xE2, 0xA3, 0x96, 0x34, 0x7C, 0xD3, 0x92, 0xFD, 0x34, 0xED, 0x46, 0xE7, 0x96, 0x65,
|
||||
0xB5, 0x37, 0x79, 0x94, 0x8D, 0x08, 0x13, 0xF9, 0x85, 0xBC, 0xCC, 0xFD, 0xEE, 0x8C, 0x68, 0x9A,
|
||||
0x8F, 0xE7, 0x3E, 0x67, 0x03, 0x3A, 0x9C, 0x1A, 0xE6, 0xA6, 0x41, 0x7C, 0xBA, 0xCB, 0xF7, 0xF0,
|
||||
0x69, 0x4C, 0x19, 0x79, 0xCC, 0xFB, 0xA4, 0x93, 0xE2, 0x01, 0x89, 0x4F, 0xDB, 0x2D, 0xBD, 0x55,
|
||||
0xF5, 0xA5, 0x8C, 0xA6, 0x07, 0x1B, 0x91, 0x90, 0xB1, 0x3B, 0x43, 0xBE, 0xC5, 0x47, 0x64, 0xEE,
|
||||
0x57, 0xB6, 0x28, 0x3E, 0xE4, 0x84, 0x8A, 0x27, 0xEC, 0xE9, 0xFD, 0x1D, 0x9E, 0x8A, 0x0E, 0x39,
|
||||
0x21, 0x51, 0x26, 0x48, 0xFE, 0x79, 0xAA, 0x9D, 0xB9, 0x2B, 0xA2, 0x8A, 0xFB, 0xC4, 0x63, 0x6A,
|
||||
0x2A, 0x7A, 0xFE, 0x1C, 0x47, 0x87, 0x85, 0xEB, 0xB2, 0x40, 0x89, 0x20, 0xF0, 0x21, 0x79, 0x32,
|
||||
0x18, 0xF4, 0xA4, 0x2C, 0xA1, 0xE2, 0x74, 0x8B, 0xD0, 0xE1, 0x81, 0xE8, 0x40, 0x30, 0xF3, 0xD7,
|
||||
0x9B, 0x95, 0x08, 0xC3, 0x98, 0xEF, 0xE3, 0x78, 0x37, 0xC1, 0x2C, 0xA5, 0x79, 0x7C, 0x1C, 0xF7,
|
||||
0xC6, 0x84, 0xF4, 0x3B, 0xDE, 0x2C, 0xC4, 0x45, 0x76, 0x25, 0x48, 0x3F, 0xE1, 0x8C, 0x6C, 0xB3,
|
||||
0x01, 0x9F, 0x37, 0x2B, 0x86, 0x07, 0x2C, 0x1B, 0x7D, 0x89, 0xE3, 0x8C, 0x74, 0x82, 0x60, 0x16,
|
||||
0xB5, 0xD2, 0xAE, 0xF3, 0xEA, 0x65, 0xFB, 0x0B, 0x01, 0x28, 0xFB, 0x29, 0x96, 0xF9, 0x38, 0x5A,
|
||||
0xFA, 0x81, 0x4C, 0x03, 0x8E, 0x65, 0xD1, 0x39, 0xEE, 0xEB, 0x46, 0x38, 0x33, 0x2D, 0x02, 0xFA,
|
||||
0xFE, 0x2C, 0xD6, 0x92, 0x45, 0xEF, 0xA9, 0x1D, 0xA7, 0xCE, 0xA6, 0x77, 0xEF, 0xF2, 0x69, 0x5E,
|
||||
0xB7, 0x59, 0x9F, 0x9C, 0x54, 0xFD, 0x55, 0xA3, 0x3A, 0x55, 0xCD, 0x9C, 0xDE, 0x61, 0xB2, 0x9E,
|
||||
0xE7, 0xB8, 0x37, 0x38, 0x5F, 0x78, 0x8D, 0xF9, 0xCE, 0x03, 0x44, 0x59, 0x2A, 0xF8, 0xA8, 0x3B,
|
||||
0x55, 0x7E, 0x81, 0x47, 0xA4, 0xD3, 0xED, 0x6D, 0x3E, 0xFA, 0x6A, 0xA3, 0xDB, 0xDD, 0xD8, 0xD9,
|
||||
0xDE, 0xE8, 0xCD, 0x22, 0x2D, 0xAB, 0x2A, 0x61, 0x06, 0x3C, 0xC2, 0xF1, 0x8E, 0xBC, 0x35, 0x89,
|
||||
0x83, 0x62, 0xF8, 0xE5, 0xB6, 0x8A, 0x3C, 0x25, 0x2C, 0xE5, 0xC9, 0x56, 0x21, 0x9D, 0x5F, 0x6B,
|
||||
0x65, 0x7B, 0x15, 0xD9, 0x5E, 0x55, 0x46, 0x47, 0x78, 0x48, 0x16, 0xC1, 0x66, 0x97, 0x3A, 0xD1,
|
||||
0x9E, 0x2A, 0x5A, 0x8A, 0x34, 0xA2, 0xAC, 0x77, 0xC0, 0xB9, 0xD8, 0x66, 0x82, 0x24, 0x47, 0x38,
|
||||
0x2E, 0xE4, 0x4B, 0x86, 0xCB, 0xD2, 0x38, 0xBD, 0xA7, 0xA8, 0x4B, 0x45, 0x15, 0x4E, 0x15, 0xBB,
|
||||
0xA7, 0x63, 0xD2, 0xB1, 0x95, 0x14, 0x97, 0x0C, 0x97, 0xBA, 0x4E, 0x6A, 0xF0, 0xF6, 0xE5, 0x0F,
|
||||
0xFF, 0xFD, 0xF8, 0x97, 0xC6, 0x5F, 0xAD, 0x90, 0xCE, 0xFF, 0x31, 0x65, 0x5D, 0x9C, 0xE0, 0xCA,
|
||||
0x82, 0xBB, 0x58, 0x71, 0x79, 0x30, 0x7C, 0x72, 0x55, 0x30, 0x45, 0x71, 0x69, 0x30, 0x15, 0xD9,
|
||||
0x65, 0xCB, 0x22, 0xF1, 0x9A, 0xA5, 0xA9, 0xCB, 0x7C, 0xDD, 0x02, 0xB9, 0xEF, 0x5E, 0xA0, 0xB3,
|
||||
0xEF, 0x7F, 0x39, 0x7F, 0xF5, 0xE7, 0x5A, 0x16, 0x48, 0xB7, 0x6C, 0x6F, 0xA8, 0x40, 0xB0, 0x46,
|
||||
0x81, 0xDE, 0x3C, 0x3F, 0x7B, 0xF1, 0xF7, 0x5A, 0x16, 0x48, 0x97, 0x95, 0x1B, 0x2A, 0x90, 0xF3,
|
||||
0xEE, 0x05, 0x3A, 0x7F, 0xF9, 0xED, 0xD9, 0xAF, 0xAF, 0xDF, 0xFE, 0xF6, 0xEA, 0x3D, 0xD4, 0xC8,
|
||||
0x06, 0x1F, 0x5E, 0x95, 0x74, 0xA9, 0xB9, 0xA1, 0x2A, 0xD5, 0x7E, 0x10, 0x59, 0xBA, 0x3B, 0xE5,
|
||||
0xC7, 0x0F, 0x92, 0x6E, 0x56, 0x1F, 0x31, 0x48, 0x96, 0xB7, 0xA6, 0x28, 0xE9, 0xE6, 0x75, 0x43,
|
||||
0x75, 0xD2, 0x0D, 0xE5, 0xBA, 0x28, 0xFD, 0xFC, 0xFA, 0xEC, 0x9F, 0xDF, 0xCF, 0x9E, 0xBF, 0x39,
|
||||
0xFF, 0xF7, 0xA7, 0xB3, 0x17, 0x7F, 0xBC, 0x7D, 0xF5, 0x9D, 0xE5, 0xAF, 0x25, 0x56, 0xBA, 0x59,
|
||||
0x7D, 0x7C, 0x1B, 0x88, 0x67, 0x2C, 0xE6, 0xD1, 0xA1, 0x35, 0x88, 0xF3, 0x33, 0x00, 0x2B, 0xE2,
|
||||
0x4C, 0x24, 0x3C, 0xB6, 0x12, 0x92, 0x8A, 0x84, 0x4E, 0x54, 0xA9, 0xF5, 0x89, 0xFC, 0x6A, 0x1F,
|
||||
0x51, 0x1C, 0x5B, 0x58, 0x08, 0xC2, 0xF2, 0xB6, 0x4F, 0xD7, 0xB2, 0xA0, 0xC1, 0x87, 0x53, 0xD0,
|
||||
0x1A, 0x5B, 0xF6, 0x6E, 0x4C, 0x70, 0x4A, 0xAC, 0x1E, 0x89, 0x49, 0x24, 0xAC, 0x59, 0xE7, 0xD6,
|
||||
0x64, 0x1E, 0x6B, 0x59, 0x35, 0xB4, 0x86, 0x55, 0xEB, 0xE1, 0xD1, 0x38, 0x26, 0x6B, 0x59, 0xAE,
|
||||
0xF0, 0xC3, 0x29, 0x57, 0x8D, 0xFD, 0xE2, 0xD3, 0x8C, 0xAD, 0x65, 0x75, 0xEC, 0xF7, 0x76, 0x6C,
|
||||
0x71, 0xD1, 0x71, 0x64, 0x71, 0x1C, 0xB5, 0x74, 0x5A, 0xDF, 0x7E, 0xC8, 0xE3, 0x3E, 0x49, 0x2A,
|
||||
0x27, 0xD9, 0x44, 0x92, 0x80, 0x05, 0xD9, 0xEE, 0x17, 0x13, 0x2C, 0x35, 0xE9, 0x8E, 0xCD, 0xA7,
|
||||
0xA7, 0xD9, 0x93, 0x83, 0xFC, 0x84, 0x48, 0x1D, 0x3D, 0x22, 0xBB, 0xBC, 0x27, 0x70, 0x22, 0xBA,
|
||||
0x9C, 0x32, 0xA1, 0x1E, 0xA1, 0x97, 0xC4, 0x4A, 0xAC, 0xE3, 0xE9, 0xEB, 0x80, 0x52, 0xAF, 0x8B,
|
||||
0x16, 0xF5, 0x88, 0x9B, 0xA6, 0x02, 0xB3, 0x88, 0x74, 0x50, 0xE0, 0x35, 0x6D, 0xD7, 0xF3, 0x61,
|
||||
0x88, 0x10, 0x44, 0xF6, 0xFC, 0x89, 0x5C, 0xD8, 0x55, 0xAF, 0x2C, 0xC1, 0x79, 0xC2, 0x3A, 0x10,
|
||||
0xF8, 0x4D, 0x0F, 0x86, 0x36, 0x0C, 0x01, 0x44, 0x4E, 0xE1, 0x34, 0x37, 0x2B, 0x4E, 0x38, 0x13,
|
||||
0xFC, 0xE1, 0xE4, 0x31, 0xAD, 0x1E, 0xC5, 0x57, 0xDB, 0xE7, 0x4E, 0xDD, 0x18, 0x47, 0x64, 0x84,
|
||||
0x93, 0xC3, 0x52, 0xE9, 0x26, 0x29, 0x50, 0x16, 0x42, 0xC4, 0x79, 0xD2, 0xA7, 0x4C, 0xE6, 0x33,
|
||||
0x2D, 0xB7, 0x5B, 0x96, 0x6D, 0x3B, 0xCD, 0xD0, 0x09, 0x00, 0xF4, 0xDC, 0xD0, 0x05, 0x20, 0xB8,
|
||||
0x0D, 0x61, 0xD3, 0x0B, 0x42, 0x1F, 0x05, 0xB6, 0x63, 0x7B, 0xC8, 0x45, 0xE5, 0x28, 0x2D, 0x6D,
|
||||
0x98, 0x76, 0xAB, 0xD2, 0xDF, 0xEC, 0x20, 0x53, 0x39, 0x20, 0xA3, 0xBA, 0x43, 0x5D, 0xA5, 0x3C,
|
||||
0xA5, 0xCD, 0xBA, 0xDA, 0x5E, 0x71, 0x92, 0x25, 0x1A, 0xE7, 0xFD, 0xA9, 0xE9, 0x51, 0x5B, 0x2F,
|
||||
0x70, 0xD9, 0x22, 0x38, 0x7F, 0x7B, 0x35, 0x81, 0x65, 0x99, 0x93, 0x8A, 0x6A, 0xB2, 0x5C, 0x06,
|
||||
0x3C, 0x8E, 0xF9, 0xF1, 0xEC, 0xB5, 0x51, 0xA5, 0xAB, 0xB2, 0xEE, 0xAA, 0x60, 0x1B, 0x6C, 0x18,
|
||||
0x93, 0xF2, 0x2A, 0x5B, 0x36, 0x5E, 0x18, 0x42, 0x66, 0x77, 0x9A, 0x60, 0xD0, 0x04, 0x93, 0xBF,
|
||||
0xDB, 0x4B, 0x1F, 0x2A, 0x71, 0x0B, 0x8F, 0x6B, 0x0D, 0xEB, 0x01, 0xC3, 0xFB, 0x57, 0x0C, 0x6E,
|
||||
0x26, 0xA9, 0xDE, 0x1C, 0x2E, 0xCF, 0xAB, 0xDA, 0xE3, 0x6E, 0x96, 0xB0, 0x2B, 0x12, 0x9F, 0x4B,
|
||||
0x26, 0xD9, 0x14, 0x7C, 0x32, 0xFC, 0x0D, 0xD6, 0xEF, 0x09, 0x3E, 0xDE, 0xA3, 0xE2, 0x60, 0x93,
|
||||
0xA6, 0xF9, 0xA6, 0x95, 0xB2, 0x8C, 0x8A, 0xD3, 0xFB, 0x59, 0x72, 0x84, 0x45, 0x96, 0x54, 0x0B,
|
||||
0x52, 0xF8, 0x5F, 0xDA, 0xC3, 0xA6, 0x7C, 0xEA, 0xCA, 0xC1, 0xCA, 0x88, 0x62, 0x69, 0xCE, 0x55,
|
||||
0xFB, 0x45, 0x13, 0xD6, 0x4C, 0x66, 0xDA, 0x51, 0x96, 0x92, 0x9E, 0x48, 0x70, 0xBE, 0x6E, 0x77,
|
||||
0xE4, 0x8A, 0x29, 0x1E, 0x3E, 0xD5, 0xF6, 0xE2, 0xF6, 0xB9, 0x84, 0xEF, 0xFB, 0x01, 0xDA, 0x0F,
|
||||
0xBD, 0x30, 0x90, 0x7F, 0x9E, 0x3B, 0x01, 0x1A, 0x81, 0xD0, 0x01, 0x0E, 0xF2, 0x5C, 0xDF, 0x75,
|
||||
0x6B, 0x02, 0x6D, 0x1B, 0xA0, 0x0D, 0xD0, 0x06, 0xE8, 0x55, 0x03, 0x1D, 0x38, 0x08, 0xB9, 0x30,
|
||||
0xB0, 0x51, 0x50, 0x00, 0xED, 0x21, 0x68, 0xBB, 0x3E, 0xAC, 0xFB, 0x84, 0x86, 0x06, 0x68, 0x03,
|
||||
0xB4, 0x01, 0x7A, 0xE5, 0x40, 0xBB, 0xC0, 0x0E, 0x01, 0x70, 0xD1, 0x7C, 0xCB, 0x9D, 0xEF, 0xC1,
|
||||
0x7D, 0xD7, 0x07, 0xA0, 0x2E, 0xD0, 0x8E, 0x01, 0xDA, 0x00, 0x6D, 0x80, 0x5E, 0x39, 0xD0, 0x28,
|
||||
0x90, 0xDF, 0xF3, 0x3D, 0xC7, 0xF7, 0xE7, 0x40, 0x43, 0xE0, 0x48, 0x9A, 0xA1, 0x67, 0xD7, 0x04,
|
||||
0xDA, 0x35, 0x40, 0x1B, 0xA0, 0x0D, 0xD0, 0x2B, 0x07, 0x3A, 0x08, 0x01, 0x0C, 0x90, 0x33, 0xDF,
|
||||
0x70, 0x7B, 0xB6, 0x04, 0xDA, 0xF5, 0xDC, 0xB0, 0x26, 0xCE, 0x9E, 0xC1, 0xD9, 0xE0, 0x6C, 0x70,
|
||||
0x5E, 0x35, 0xCE, 0xC8, 0x09, 0xA0, 0x64, 0xD8, 0xF3, 0x0A, 0x9E, 0x1D, 0x14, 0x00, 0x14, 0xB8,
|
||||
0x41, 0x4D, 0x9E, 0x7D, 0xC3, 0xB3, 0xE1, 0xD9, 0xF0, 0xBC, 0x72, 0x9E, 0x5D, 0x1B, 0x78, 0x30,
|
||||
0x74, 0x1D, 0x77, 0xB6, 0xDF, 0x46, 0x00, 0xC2, 0x10, 0x48, 0xC8, 0x61, 0x4D, 0xA0, 0x03, 0x03,
|
||||
0xB4, 0x01, 0xDA, 0x00, 0xBD, 0x72, 0xA0, 0x43, 0xD7, 0x77, 0x80, 0x0F, 0x90, 0x3D, 0x07, 0x1A,
|
||||
0x06, 0x8E, 0x1D, 0x38, 0xD0, 0xAE, 0xFB, 0x84, 0x46, 0x06, 0x68, 0x03, 0xB4, 0x01, 0x7A, 0xE5,
|
||||
0x40, 0x23, 0x24, 0x71, 0x96, 0x3B, 0xEE, 0xE2, 0x25, 0xB4, 0x1F, 0x02, 0xD7, 0x05, 0x76, 0xDD,
|
||||
0x77, 0xD0, 0xA1, 0xE1, 0xD9, 0xF0, 0x6C, 0x78, 0xBE, 0x2E, 0xCF, 0xED, 0xD6, 0xE2, 0x7F, 0xEE,
|
||||
0xDA, 0xAD, 0xC5, 0xAF, 0xEA, 0xDB, 0xF9, 0x2F, 0xF3, 0x3B, 0xB7, 0xFE, 0x07, 0x50, 0x4B, 0x07,
|
||||
0x08, 0xDD, 0x90, 0xD9, 0xA9, 0x92, 0x05, 0x00, 0x00, 0xE9, 0x3F, 0x00, 0x00, 0x50, 0x4B, 0x01,
|
||||
0x02, 0x14, 0x00, 0x14, 0x00, 0x08, 0x08, 0x08, 0x00, 0x22, 0x6D, 0x34, 0x55, 0x50, 0x7D, 0x0A,
|
||||
0x8A, 0xCC, 0x05, 0x00, 0x00, 0xEA, 0x33, 0x00, 0x00, 0x11, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x77, 0x70, 0x6D, 0x7A, 0x2F,
|
||||
0x74, 0x65, 0x6D, 0x70, 0x6C, 0x61, 0x74, 0x65, 0x2E, 0x6B, 0x6D, 0x6C, 0x50, 0x4B, 0x01, 0x02,
|
||||
0x14, 0x00, 0x14, 0x00, 0x08, 0x08, 0x08, 0x00, 0x22, 0x6D, 0x34, 0x55, 0xDD, 0x90, 0xD9, 0xA9,
|
||||
0x92, 0x05, 0x00, 0x00, 0xE9, 0x3F, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0B, 0x06, 0x00, 0x00, 0x77, 0x70, 0x6D, 0x7A, 0x2F, 0x77,
|
||||
0x61, 0x79, 0x6C, 0x69, 0x6E, 0x65, 0x73, 0x2E, 0x77, 0x70, 0x6D, 0x6C, 0x50, 0x4B, 0x05, 0x06,
|
||||
0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x02, 0x00, 0x7F, 0x00, 0x00, 0x00, 0xDD, 0x0B, 0x00, 0x00,
|
||||
0x00, 0x00
|
||||
0x5C, 0xCD, 0x72, 0xDB, 0x36, 0x10, 0xBE, 0xE7, 0x29, 0x3C, 0x3E, 0xA7, 0x12, 0x00, 0xFE, 0x80,
|
||||
0xCC, 0x28, 0xCC, 0xA4, 0x76, 0xEC, 0x64, 0x26, 0x6D, 0x34, 0x91, 0x53, 0x4F, 0x8F, 0x30, 0x05,
|
||||
0x49, 0xA8, 0x49, 0x42, 0x25, 0xC1, 0xC8, 0xCE, 0xB1, 0xA7, 0x3E, 0x4B, 0xDF, 0xA0, 0x4F, 0xD4,
|
||||
0x3E, 0x46, 0xC1, 0x3F, 0x89, 0xA0, 0x40, 0xC5, 0x36, 0xE3, 0xD4, 0x96, 0xE9, 0x83, 0x47, 0xC2,
|
||||
0xEE, 0x7E, 0xF8, 0xDB, 0xFD, 0x16, 0x00, 0x41, 0x8D, 0x5E, 0x5D, 0x85, 0xC1, 0xC1, 0x67, 0x1A,
|
||||
0x27, 0x8C, 0x47, 0x2F, 0x0F, 0xE1, 0x00, 0x1C, 0x1E, 0xD0, 0xC8, 0xE7, 0x53, 0x16, 0xCD, 0x5F,
|
||||
0x1E, 0x7E, 0x3A, 0x3B, 0xF9, 0xC1, 0x39, 0x7C, 0xE5, 0x3D, 0x1B, 0x5D, 0x4A, 0x2D, 0xA9, 0x19,
|
||||
0x25, 0x2F, 0x0F, 0x17, 0x42, 0x2C, 0x5F, 0x0C, 0x87, 0xAB, 0xD5, 0x6A, 0xC0, 0x97, 0x34, 0x9A,
|
||||
0xB3, 0x64, 0x10, 0x51, 0x31, 0x94, 0x1A, 0x43, 0x34, 0x40, 0x87, 0x85, 0xDA, 0x8B, 0xD5, 0x32,
|
||||
0x0C, 0x14, 0xDD, 0xE9, 0x6F, 0x6C, 0xE0, 0xF3, 0x70, 0x28, 0x05, 0x5F, 0x86, 0xB2, 0x9E, 0x81,
|
||||
0x71, 0xE8, 0x3D, 0x3B, 0x38, 0x18, 0x1D, 0x73, 0x3F, 0x0D, 0x69, 0x24, 0xB2, 0x2F, 0xF2, 0x6B,
|
||||
0x66, 0xF7, 0xC2, 0x8F, 0x29, 0x11, 0xF4, 0x8C, 0x85, 0xD4, 0x83, 0x36, 0xB6, 0x80, 0x6D, 0x23,
|
||||
0xD3, 0x76, 0x0C, 0x67, 0x34, 0x6C, 0x8A, 0x6B, 0x46, 0xE9, 0x72, 0xDA, 0x30, 0x32, 0x90, 0x83,
|
||||
0x5D, 0x58, 0x1A, 0xD5, 0xC4, 0x35, 0xA3, 0x90, 0x25, 0x59, 0xCF, 0x8F, 0x78, 0x34, 0x63, 0xF3,
|
||||
0x42, 0x50, 0x89, 0x66, 0xC1, 0xF5, 0x19, 0x3F, 0x27, 0xD7, 0x01, 0x8B, 0xE8, 0x4F, 0x7C, 0x4A,
|
||||
0xBD, 0x84, 0xCC, 0x68, 0x70, 0x5D, 0xC2, 0x6D, 0x49, 0x55, 0x5B, 0x16, 0xB1, 0x64, 0xF1, 0xDA,
|
||||
0x17, 0x12, 0xDB, 0x9B, 0xF3, 0xB7, 0x3C, 0xA4, 0x95, 0x5D, 0x5D, 0xA2, 0xD8, 0xD0, 0x2B, 0x26,
|
||||
0x3E, 0x44, 0x1F, 0x8F, 0xDE, 0xF3, 0x44, 0x78, 0xF4, 0x8A, 0xFA, 0xA9, 0xA0, 0xD9, 0xE7, 0x42,
|
||||
0xB7, 0x34, 0x57, 0x94, 0x1A, 0xE6, 0xB9, 0x45, 0x21, 0x5A, 0xD7, 0xFC, 0x23, 0xF1, 0x2F, 0xD7,
|
||||
0xA6, 0xDB, 0x0A, 0x0A, 0x82, 0x20, 0x97, 0xF4, 0xC3, 0x6C, 0x36, 0x91, 0x6A, 0x31, 0x13, 0xD7,
|
||||
0x6F, 0x29, 0x9B, 0x2F, 0x84, 0x87, 0x40, 0x69, 0xAF, 0x17, 0x2B, 0x08, 0xF3, 0x80, 0x5F, 0x90,
|
||||
0xE0, 0x2C, 0x26, 0x51, 0xC2, 0x32, 0x7C, 0x12, 0x4C, 0x96, 0x94, 0x4E, 0x3D, 0x68, 0x95, 0x18,
|
||||
0x6D, 0x0A, 0x0A, 0xCA, 0x34, 0xE6, 0x11, 0x7D, 0x17, 0xCD, 0x78, 0x55, 0xAC, 0x08, 0xDE, 0x44,
|
||||
0x69, 0xF8, 0x0B, 0x09, 0x52, 0xEA, 0x61, 0x5C, 0xA2, 0x36, 0xCA, 0x75, 0x56, 0x93, 0xF4, 0x62,
|
||||
0xA3, 0x00, 0xEA, 0x76, 0x8A, 0xA4, 0x6A, 0xC7, 0x50, 0xDF, 0x90, 0x02, 0x70, 0x29, 0x67, 0x9D,
|
||||
0x93, 0xA9, 0xAE, 0x85, 0xA5, 0x68, 0x03, 0x68, 0xDB, 0x25, 0xD6, 0x96, 0x44, 0x6F, 0xA9, 0x6D,
|
||||
0xA7, 0x4E, 0xA6, 0x37, 0x1F, 0xF3, 0x62, 0x5C, 0xDF, 0x45, 0x53, 0x7A, 0xD5, 0xB4, 0x57, 0x85,
|
||||
0x6A, 0x57, 0xB7, 0xFA, 0x54, 0x96, 0x6B, 0xE2, 0x63, 0x74, 0xC2, 0x83, 0x29, 0x8D, 0x1B, 0xBE,
|
||||
0x43, 0xC3, 0x65, 0x90, 0xC5, 0xD7, 0xF5, 0x92, 0x7A, 0x2B, 0x72, 0xBD, 0xE4, 0x2C, 0x12, 0x95,
|
||||
0xE3, 0xD4, 0x65, 0x5A, 0xAB, 0x77, 0xD3, 0x75, 0x5B, 0x6B, 0x45, 0x8A, 0xEA, 0xAA, 0x08, 0xB5,
|
||||
0x23, 0xCE, 0x63, 0xC9, 0x4D, 0x52, 0x61, 0x72, 0x9D, 0x8C, 0x49, 0x4C, 0xC2, 0xE6, 0x48, 0xF8,
|
||||
0x6B, 0x8D, 0x3C, 0x2C, 0xCF, 0x4F, 0x27, 0x8E, 0x59, 0xF1, 0x86, 0x2A, 0x6A, 0x18, 0x2E, 0x72,
|
||||
0x87, 0xCE, 0x25, 0x31, 0x95, 0x4D, 0x60, 0x9F, 0xE9, 0x19, 0x9F, 0x08, 0x12, 0x8B, 0x71, 0xAD,
|
||||
0x33, 0x35, 0xAD, 0xE6, 0x14, 0x94, 0xC3, 0x2B, 0x99, 0x33, 0xEF, 0xE9, 0xE9, 0x78, 0x52, 0x0D,
|
||||
0x6E, 0x43, 0xA2, 0x0E, 0xFD, 0x57, 0x7B, 0x56, 0xC0, 0x93, 0x54, 0xF0, 0x93, 0x20, 0xAB, 0xBC,
|
||||
0x08, 0x99, 0x2A, 0xA4, 0x9A, 0xE5, 0x9A, 0x80, 0x2C, 0x43, 0x15, 0x02, 0xA0, 0x84, 0xA1, 0x2E,
|
||||
0x82, 0x7D, 0x12, 0xB0, 0x02, 0xED, 0x4D, 0x44, 0x2E, 0x82, 0x8D, 0x0F, 0x6E, 0x09, 0xD4, 0x7A,
|
||||
0x58, 0x28, 0x01, 0xC7, 0x4C, 0xF8, 0x8B, 0x7C, 0x68, 0x42, 0x12, 0xA5, 0x24, 0xA8, 0x6A, 0x6B,
|
||||
0x08, 0x35, 0x2D, 0x3C, 0x2F, 0x3D, 0xE6, 0x2D, 0x25, 0x59, 0xE6, 0xD1, 0x4E, 0xEC, 0x4A, 0xD5,
|
||||
0xC9, 0xA1, 0x66, 0x3C, 0x08, 0xF8, 0xAA, 0xA4, 0xE1, 0xCD, 0x78, 0x6E, 0xE9, 0xED, 0x86, 0x7A,
|
||||
0x1D, 0xCD, 0x6B, 0x3D, 0xD5, 0x0A, 0x5B, 0x00, 0xA4, 0x67, 0xE4, 0xCE, 0xE1, 0x81, 0x01, 0xC8,
|
||||
0xFF, 0x9E, 0x6F, 0x7D, 0x68, 0xA0, 0xAE, 0x2D, 0x76, 0x37, 0x49, 0xEA, 0xA8, 0x31, 0xDC, 0x26,
|
||||
0x57, 0x7D, 0xE9, 0xEB, 0xA3, 0xA9, 0x1B, 0xF5, 0xB3, 0x34, 0x8E, 0xF2, 0x61, 0x12, 0x3C, 0x6F,
|
||||
0xDB, 0xEB, 0x68, 0x3A, 0x11, 0x7C, 0x79, 0xCE, 0xC4, 0xE2, 0x98, 0x25, 0x3E, 0x8F, 0x04, 0x8B,
|
||||
0x52, 0x49, 0xF9, 0x47, 0x69, 0xFC, 0x99, 0x88, 0x34, 0xA6, 0xDA, 0xDA, 0xD6, 0x28, 0x9A, 0x9A,
|
||||
0x3E, 0x25, 0x74, 0x22, 0x62, 0x92, 0xB9, 0xCF, 0x7B, 0x39, 0x53, 0x1E, 0x54, 0x10, 0x9A, 0xD2,
|
||||
0x0A, 0x60, 0x1C, 0x10, 0x9F, 0x86, 0x24, 0xBE, 0xAC, 0x0D, 0x56, 0x63, 0xF0, 0x64, 0xC9, 0x26,
|
||||
0xAA, 0x93, 0x7A, 0xF9, 0xC1, 0x01, 0x84, 0xC6, 0xC0, 0x35, 0x0D, 0x88, 0x0C, 0x8C, 0x5D, 0x0B,
|
||||
0x98, 0xCF, 0x11, 0x1A, 0x58, 0x18, 0x9B, 0xAE, 0xE1, 0x3A, 0xB6, 0x69, 0xD7, 0x31, 0x86, 0x5A,
|
||||
0x90, 0xD1, 0x50, 0x3B, 0x55, 0x4C, 0x99, 0x18, 0x56, 0x9F, 0x86, 0x75, 0x32, 0x0E, 0x02, 0xB6,
|
||||
0x4C, 0x38, 0x9B, 0x6E, 0x85, 0x5E, 0x53, 0xA2, 0x25, 0xA1, 0x9A, 0xFE, 0x42, 0xAB, 0x96, 0x26,
|
||||
0xF4, 0x54, 0x09, 0xED, 0x6A, 0x91, 0xD3, 0x28, 0x6F, 0x33, 0x2B, 0xD3, 0x72, 0xD3, 0x4A, 0x61,
|
||||
0x10, 0x4D, 0x5D, 0x35, 0x77, 0xD2, 0xD4, 0xD8, 0x1E, 0xBA, 0x6B, 0xA5, 0xCC, 0x47, 0x5A, 0xEC,
|
||||
0x37, 0xA2, 0x6D, 0x63, 0xC5, 0x3B, 0xC0, 0xC6, 0x52, 0xE7, 0x35, 0x6B, 0xBE, 0xCC, 0x57, 0x38,
|
||||
0xA7, 0x31, 0x4F, 0x97, 0x8A, 0xBB, 0x34, 0x85, 0xB5, 0xDC, 0xA3, 0x96, 0xEE, 0x32, 0xCA, 0xD3,
|
||||
0x82, 0x1A, 0xA0, 0x7A, 0xE9, 0x2E, 0x90, 0x37, 0xD1, 0xB4, 0x15, 0x62, 0x2D, 0xDB, 0x05, 0x50,
|
||||
0xAC, 0x4A, 0xE9, 0xEF, 0xA9, 0x5C, 0xB1, 0xD3, 0x6D, 0x0C, 0x95, 0xF9, 0x54, 0xFB, 0xB3, 0x98,
|
||||
0xCD, 0xE7, 0x9B, 0x24, 0xDE, 0xAA, 0x90, 0xE7, 0x2B, 0xB9, 0xDC, 0xF6, 0x17, 0xF5, 0x24, 0xB8,
|
||||
0xAD, 0xA2, 0x04, 0xD3, 0xEE, 0x7A, 0xEA, 0xB5, 0xB4, 0xD7, 0xBF, 0x35, 0x2D, 0xEA, 0x8C, 0xA8,
|
||||
0xCA, 0x72, 0x35, 0x9B, 0x12, 0xC1, 0xE3, 0x93, 0x34, 0xF2, 0xBD, 0x6C, 0x9D, 0x3A, 0x5E, 0x70,
|
||||
0xC1, 0x15, 0x73, 0x45, 0xE5, 0x46, 0x40, 0x0D, 0x67, 0xAC, 0x2B, 0xCF, 0x58, 0x20, 0xD7, 0x8D,
|
||||
0xB3, 0x19, 0xBB, 0xF2, 0xFE, 0xFD, 0xF3, 0xAF, 0x7F, 0xFE, 0xF8, 0xBB, 0xF2, 0xE6, 0x9A, 0x40,
|
||||
0x6B, 0x78, 0xE7, 0x65, 0x9A, 0x0A, 0xB3, 0x0E, 0x9A, 0x71, 0x61, 0xF2, 0x9E, 0x46, 0x89, 0x8A,
|
||||
0xD5, 0xAE, 0xA1, 0xF6, 0xBD, 0x6D, 0x88, 0xB6, 0x3A, 0xAF, 0x68, 0xD6, 0x29, 0xB2, 0x2D, 0xD8,
|
||||
0x24, 0x79, 0x36, 0xE9, 0xFB, 0x5B, 0x11, 0x3A, 0xB0, 0x4D, 0x64, 0x9A, 0xD0, 0x29, 0x08, 0x5D,
|
||||
0xEE, 0xF3, 0x0C, 0xD3, 0x72, 0x80, 0x8D, 0x60, 0x47, 0x4A, 0x87, 0x3D, 0xA5, 0xEF, 0x0B, 0xA5,
|
||||
0xC3, 0x2E, 0x94, 0xAE, 0x31, 0xBE, 0x2D, 0xA5, 0x6B, 0x20, 0x7A, 0x4A, 0xBF, 0x33, 0xA5, 0x27,
|
||||
0xD9, 0xE8, 0x7F, 0xA4, 0xBE, 0x0C, 0xE8, 0xEF, 0x48, 0xEA, 0xE8, 0xA9, 0x92, 0xFA, 0xF7, 0x98,
|
||||
0x50, 0xBE, 0xBC, 0xEF, 0xF9, 0xEC, 0x38, 0x2D, 0x8F, 0x31, 0x35, 0x22, 0x03, 0xD8, 0xAE, 0x09,
|
||||
0x1C, 0x6C, 0x95, 0xA9, 0x11, 0x02, 0x68, 0xC8, 0x7F, 0x26, 0xB4, 0x3A, 0xA6, 0x46, 0xD4, 0xA7,
|
||||
0xC6, 0x7D, 0x49, 0x8D, 0xA8, 0x4B, 0x6A, 0xD4, 0x18, 0xDF, 0x36, 0x35, 0x6A, 0x20, 0xFA, 0xD4,
|
||||
0x78, 0x67, 0x26, 0x2D, 0x0E, 0xD7, 0x3E, 0x72, 0x21, 0x83, 0xF9, 0xFE, 0xB8, 0xB4, 0x5E, 0x4B,
|
||||
0x3E, 0xD0, 0xE4, 0x22, 0xE1, 0x41, 0x2A, 0x68, 0x7E, 0x3A, 0xA6, 0x9C, 0xF3, 0xD5, 0x94, 0x76,
|
||||
0x40, 0xE5, 0xA7, 0x81, 0x85, 0x6A, 0x79, 0x9E, 0x08, 0x15, 0x94, 0x6D, 0xF9, 0xCD, 0xC0, 0xD4,
|
||||
0xA3, 0xBC, 0x16, 0xF1, 0xCE, 0x2E, 0x06, 0x81, 0x52, 0x2D, 0x68, 0x74, 0xAE, 0x21, 0xBE, 0x11,
|
||||
0x94, 0xAE, 0x51, 0x4D, 0xE9, 0x0E, 0xA0, 0x5F, 0xC9, 0x6A, 0x47, 0x93, 0x9A, 0xD2, 0x9B, 0x00,
|
||||
0xE9, 0x1A, 0xD4, 0x10, 0x7E, 0xD5, 0x0D, 0xB2, 0x27, 0x69, 0x2D, 0x63, 0xD4, 0x10, 0xDF, 0x08,
|
||||
0xAA, 0x15, 0xA4, 0x4F, 0xEE, 0x65, 0x72, 0x87, 0x36, 0x46, 0x10, 0x39, 0x0E, 0xC2, 0x55, 0x72,
|
||||
0x87, 0xAE, 0x6B, 0x20, 0x17, 0xBA, 0xB8, 0x63, 0x72, 0x37, 0xFA, 0xE4, 0xBE, 0x2F, 0xC9, 0xDD,
|
||||
0xE8, 0x92, 0xDC, 0x35, 0xC6, 0xB7, 0x4D, 0xEE, 0x1A, 0x88, 0x3E, 0xB9, 0xDF, 0x39, 0xB9, 0x7F,
|
||||
0xE1, 0x3C, 0xBC, 0xC7, 0x0D, 0x2F, 0xF7, 0x49, 0x20, 0xF7, 0x90, 0x73, 0xB1, 0xF0, 0xCC, 0xEA,
|
||||
0x6E, 0x45, 0xBD, 0x50, 0x6B, 0xC5, 0x92, 0x4F, 0x09, 0x3D, 0xC9, 0xB4, 0x4E, 0x64, 0x6D, 0x3C,
|
||||
0xDE, 0x3C, 0x08, 0x69, 0x0A, 0x7A, 0xE2, 0x2E, 0x89, 0x1B, 0x62, 0x49, 0xD5, 0x06, 0x2E, 0x1F,
|
||||
0x40, 0xD9, 0xD8, 0xB0, 0x91, 0x2B, 0xC9, 0xDC, 0x72, 0x3B, 0xF2, 0xB6, 0xD9, 0xF3, 0xF6, 0xBE,
|
||||
0xF0, 0xB6, 0xD9, 0x85, 0xB7, 0x35, 0xC6, 0xB7, 0xE5, 0x6D, 0x0D, 0x44, 0xCF, 0xDB, 0x8F, 0xEA,
|
||||
0x11, 0x54, 0x75, 0x1F, 0xA4, 0x3F, 0xAD, 0xFC, 0xE6, 0xD3, 0xF9, 0xFF, 0x1C, 0x3F, 0xF7, 0x13,
|
||||
0xDA, 0x1F, 0x3F, 0x3F, 0xE8, 0x51, 0xEC, 0x8F, 0x9E, 0xFA, 0xA3, 0xA7, 0xFE, 0xE8, 0x69, 0x0F,
|
||||
0x03, 0xBB, 0xDF, 0x76, 0xEE, 0xC5, 0xB6, 0x13, 0xB9, 0x06, 0x30, 0xA0, 0x55, 0xDD, 0x7B, 0x34,
|
||||
0x2C, 0x80, 0x10, 0x80, 0x96, 0xDD, 0xF5, 0xE6, 0x63, 0xB5, 0x30, 0xE9, 0xB7, 0x9D, 0x8F, 0x7E,
|
||||
0xDB, 0x69, 0x6D, 0xFB, 0xE5, 0xCD, 0xB7, 0x9D, 0x1A, 0xE3, 0xDB, 0x6E, 0x3B, 0x35, 0x10, 0xFD,
|
||||
0xB6, 0xF3, 0xCE, 0xBC, 0xED, 0xA7, 0x72, 0x61, 0x1B, 0x1E, 0xB3, 0xF8, 0x67, 0x12, 0xDE, 0xE3,
|
||||
0x8A, 0xEC, 0x29, 0x72, 0xA9, 0x65, 0x01, 0x68, 0x60, 0x60, 0x96, 0xCF, 0x5E, 0xB0, 0x6B, 0x5B,
|
||||
0x10, 0x62, 0xE0, 0x5A, 0x5D, 0x9F, 0xBD, 0xD8, 0x3D, 0x99, 0x3E, 0x48, 0x32, 0xBD, 0xBF, 0x3B,
|
||||
0x3A, 0x08, 0xB8, 0x00, 0xC9, 0xB4, 0x0C, 0x0B, 0x57, 0x72, 0x2C, 0xC3, 0xC8, 0x8E, 0x88, 0x2D,
|
||||
0xD0, 0xD5, 0x95, 0x70, 0xEF, 0x4A, 0x0F, 0xD2, 0x95, 0xEE, 0x90, 0x97, 0xED, 0x2E, 0x79, 0x19,
|
||||
0x77, 0xCF, 0xCB, 0x1A, 0x88, 0x07, 0x95, 0x97, 0xC3, 0x34, 0x10, 0x6C, 0x19, 0xD0, 0x63, 0x96,
|
||||
0x08, 0xD2, 0xAC, 0xAA, 0x25, 0x3B, 0x6B, 0xD1, 0xCA, 0xA9, 0x07, 0x3A, 0x80, 0xDD, 0xF9, 0x68,
|
||||
0x3F, 0x8F, 0x95, 0xF7, 0xEE, 0x30, 0xF1, 0x7F, 0x58, 0x2C, 0xC8, 0x7D, 0x97, 0xE9, 0xB8, 0xC8,
|
||||
0xC1, 0xE5, 0x0B, 0x0A, 0x8E, 0x09, 0x4D, 0xC3, 0x42, 0x06, 0x80, 0x4E, 0x47, 0x86, 0x77, 0x7A,
|
||||
0x86, 0x7F, 0x90, 0x0C, 0x7F, 0x7F, 0xEF, 0xBA, 0x20, 0x60, 0x42, 0x60, 0xB8, 0x6E, 0xB5, 0xEC,
|
||||
0x44, 0x8E, 0x69, 0xB8, 0x08, 0xBB, 0x5D, 0x3D, 0xC9, 0xED, 0x3D, 0xE9, 0x69, 0x79, 0x12, 0xC2,
|
||||
0xB6, 0x09, 0x5D, 0x8C, 0xAA, 0xAB, 0xE1, 0xD8, 0x74, 0x11, 0x82, 0x8E, 0x2C, 0xE9, 0x7A, 0x1C,
|
||||
0xB4, 0x4E, 0x9E, 0xBD, 0x2F, 0x3D, 0x15, 0x5F, 0x32, 0x90, 0x4C, 0x72, 0xC0, 0xB2, 0xCB, 0x2D,
|
||||
0x0C, 0x06, 0x96, 0xE5, 0xBA, 0x8E, 0x6D, 0x5B, 0x46, 0x57, 0x5F, 0xEA, 0x5F, 0xC1, 0x7B, 0x62,
|
||||
0xBE, 0x24, 0x39, 0x09, 0x9B, 0x16, 0x34, 0x9D, 0xEA, 0x95, 0x15, 0x1B, 0x5A, 0x8E, 0xED, 0x22,
|
||||
0xC3, 0xE9, 0xFC, 0x36, 0x67, 0xFF, 0xCE, 0xCA, 0x53, 0xF3, 0x25, 0xEC, 0x58, 0x0E, 0xC6, 0xB0,
|
||||
0x5A, 0x78, 0x63, 0xCB, 0x34, 0x6C, 0xDB, 0x31, 0xB0, 0xDD, 0x75, 0xB9, 0x04, 0xFB, 0x2B, 0xD2,
|
||||
0x8F, 0xC7, 0x97, 0x94, 0xBD, 0xAA, 0xAE, 0x8E, 0x6F, 0xF4, 0x63, 0x49, 0x35, 0xEC, 0xD1, 0x70,
|
||||
0xF3, 0xA3, 0x48, 0xA3, 0xE1, 0xE6, 0x27, 0xCD, 0x46, 0xD9, 0xCF, 0xA2, 0x79, 0xCF, 0xFE, 0x03,
|
||||
0x50, 0x4B, 0x07, 0x08, 0xF2, 0xB2, 0xDF, 0xE7, 0xD1, 0x06, 0x00, 0x00, 0x66, 0x4D, 0x00, 0x00,
|
||||
0x50, 0x4B, 0x03, 0x04, 0x14, 0x00, 0x08, 0x08, 0x08, 0x00, 0x8A, 0x81, 0x3E, 0x56, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, 0x77, 0x70,
|
||||
0x6D, 0x7A, 0x2F, 0x77, 0x61, 0x79, 0x6C, 0x69, 0x6E, 0x65, 0x73, 0x2E, 0x77, 0x70, 0x6D, 0x6C,
|
||||
0xED, 0x5D, 0xCB, 0x72, 0xDB, 0x36, 0x14, 0xDD, 0xE7, 0x2B, 0x3C, 0x5E, 0xA7, 0x12, 0x01, 0x90,
|
||||
0x04, 0x99, 0x51, 0x94, 0x49, 0xE3, 0xB8, 0xC9, 0x8C, 0xDB, 0x78, 0x6C, 0xA5, 0x69, 0x96, 0x34,
|
||||
0x05, 0x49, 0x68, 0x48, 0x42, 0x25, 0xC1, 0xD8, 0xCE, 0xB2, 0xAB, 0x7E, 0x4B, 0xFF, 0xA0, 0x5F,
|
||||
0xD4, 0x7E, 0x46, 0xC1, 0x97, 0x44, 0x90, 0xA0, 0xAC, 0x47, 0x64, 0xCB, 0x09, 0xB2, 0xC8, 0x58,
|
||||
0xB8, 0xF7, 0x1E, 0x80, 0xB8, 0xE0, 0xB9, 0x47, 0x00, 0x4D, 0x0F, 0x5E, 0xDC, 0x84, 0xC1, 0xD1,
|
||||
0x67, 0x12, 0x27, 0x94, 0x45, 0xCF, 0x8F, 0x41, 0xCF, 0x38, 0x3E, 0x22, 0x91, 0xCF, 0xC6, 0x34,
|
||||
0x9A, 0x3E, 0x3F, 0x7E, 0x3F, 0x3A, 0xFD, 0xC1, 0x39, 0x7E, 0x31, 0x7C, 0x32, 0xF8, 0x24, 0xBC,
|
||||
0x84, 0x67, 0x94, 0x3C, 0x3F, 0x9E, 0x71, 0x3E, 0x7F, 0xD6, 0xEF, 0x5F, 0x5F, 0x5F, 0xF7, 0xD8,
|
||||
0x9C, 0x44, 0x53, 0x9A, 0xF4, 0x22, 0xC2, 0xFB, 0xC2, 0xA3, 0x0F, 0x7B, 0xF0, 0xB8, 0x70, 0x7B,
|
||||
0x76, 0x3D, 0x0F, 0x03, 0xC9, 0x77, 0xFC, 0x3B, 0xED, 0xF9, 0x2C, 0xEC, 0x0B, 0xC3, 0x97, 0xBE,
|
||||
0xE8, 0xA7, 0x87, 0x8E, 0x87, 0x4F, 0x8E, 0x8E, 0x06, 0x27, 0xCC, 0x4F, 0x43, 0x12, 0xF1, 0xEC,
|
||||
0x83, 0xF8, 0x98, 0xC5, 0x3D, 0x0B, 0x69, 0x92, 0x8D, 0xE7, 0x15, 0x8B, 0x26, 0x74, 0x5A, 0x18,
|
||||
0x2A, 0xD3, 0x24, 0xB8, 0x1D, 0xB1, 0x0F, 0xDE, 0x6D, 0x40, 0x23, 0xF2, 0x33, 0x1B, 0x93, 0x61,
|
||||
0xE2, 0x4D, 0x48, 0x70, 0x3B, 0xE8, 0xAB, 0xAD, 0x72, 0x2C, 0x8D, 0x68, 0x32, 0x7B, 0xE9, 0x73,
|
||||
0x81, 0x3D, 0x9C, 0xB2, 0x37, 0x2C, 0x24, 0x55, 0x5C, 0xDD, 0x22, 0xC5, 0x90, 0x1B, 0xCA, 0xDF,
|
||||
0x45, 0x17, 0xAF, 0xCE, 0x58, 0xC2, 0x87, 0xE4, 0x86, 0xF8, 0x29, 0x27, 0xD9, 0xCF, 0x85, 0x6F,
|
||||
0x19, 0x2E, 0x39, 0x35, 0xC2, 0xF3, 0x88, 0xC2, 0xB4, 0xE8, 0xF9, 0x47, 0xCF, 0xFF, 0xB4, 0x08,
|
||||
0x6D, 0x3B, 0x48, 0x08, 0xDC, 0xFB, 0x44, 0xDE, 0x4D, 0x26, 0x97, 0xC2, 0x2D, 0xA6, 0xFC, 0xF6,
|
||||
0x0D, 0xA1, 0xD3, 0x19, 0x1F, 0x42, 0xA3, 0x8C, 0x57, 0x9B, 0x25, 0x84, 0x69, 0xC0, 0xAE, 0xBC,
|
||||
0x60, 0x14, 0x7B, 0x51, 0x42, 0x33, 0x7C, 0x2F, 0xB8, 0x9C, 0x13, 0x32, 0x1E, 0x02, 0xAB, 0xC4,
|
||||
0xE8, 0x72, 0x90, 0x50, 0xC6, 0x31, 0x8B, 0xC8, 0xDB, 0x68, 0xC2, 0xAA, 0x66, 0xC9, 0xF0, 0x3A,
|
||||
0x4A, 0xC3, 0x5F, 0xBD, 0x20, 0x25, 0x43, 0x8C, 0x4B, 0xD4, 0x46, 0xBB, 0x2A, 0xEA, 0x32, 0xBD,
|
||||
0x5A, 0x3A, 0x18, 0xF5, 0x38, 0xC9, 0x52, 0x8D, 0xA3, 0xAF, 0x1E, 0x48, 0x01, 0x38, 0x17, 0x59,
|
||||
0x67, 0xDE, 0x58, 0x35, 0xC2, 0xD2, 0xB4, 0x04, 0xB4, 0xED, 0x12, 0xAB, 0x65, 0x51, 0x47, 0x2A,
|
||||
0xC7, 0xA9, 0xB2, 0xA9, 0xC3, 0xCF, 0x59, 0x31, 0xAF, 0x6F, 0xA3, 0x31, 0xB9, 0x69, 0xC6, 0xCB,
|
||||
0x46, 0xF9, 0x52, 0x5B, 0xD7, 0x54, 0xB6, 0x2B, 0xEE, 0x8F, 0xC1, 0x29, 0x0B, 0xC6, 0x24, 0x6E,
|
||||
0xAC, 0x1D, 0x12, 0xCE, 0x03, 0x8F, 0x93, 0xB7, 0xE3, 0x45, 0xAF, 0xB5, 0x26, 0xD5, 0x42, 0x2D,
|
||||
0xD6, 0x4F, 0x7E, 0xEB, 0xC4, 0x44, 0xF8, 0xD1, 0xCF, 0x64, 0xC4, 0x2E, 0xB9, 0x17, 0xF3, 0x73,
|
||||
0x46, 0x23, 0x2E, 0x2F, 0xDA, 0x9A, 0xB3, 0x84, 0x75, 0x5D, 0xDC, 0x80, 0xB5, 0x5E, 0x97, 0x2D,
|
||||
0xF2, 0x9A, 0xA2, 0x09, 0xF7, 0x22, 0x9F, 0x0C, 0x81, 0x01, 0x70, 0xCF, 0x32, 0xB1, 0x65, 0xDA,
|
||||
0xC8, 0xB1, 0x31, 0xAC, 0x52, 0x5D, 0xD9, 0xE5, 0xA8, 0x34, 0xF6, 0xF2, 0xFB, 0x04, 0x9A, 0x46,
|
||||
0xCF, 0xC5, 0x8E, 0x6D, 0xDB, 0xC8, 0xB0, 0x2C, 0x73, 0x11, 0x55, 0xD9, 0xA5, 0x28, 0x2F, 0xE5,
|
||||
0xEC, 0x34, 0xC8, 0x06, 0x5C, 0x2C, 0xEE, 0x6A, 0xF1, 0x37, 0xDB, 0xAB, 0xA0, 0xF3, 0xC0, 0xF3,
|
||||
0x49, 0xE8, 0xC5, 0x9F, 0x6A, 0x49, 0xCD, 0xE7, 0x60, 0xF9, 0x59, 0xB4, 0xF8, 0x8C, 0xC5, 0x82,
|
||||
0x2B, 0xC5, 0x84, 0x26, 0xF5, 0xF6, 0xA3, 0x23, 0x00, 0x50, 0xCF, 0x35, 0x11, 0x80, 0x08, 0x63,
|
||||
0xD7, 0x32, 0xCC, 0xA7, 0x10, 0xF6, 0x2C, 0x8C, 0x4D, 0x17, 0xB9, 0x8E, 0x6D, 0xDA, 0x75, 0x8C,
|
||||
0xBE, 0x12, 0x64, 0xD0, 0x6F, 0xF4, 0x56, 0x5C, 0x06, 0x95, 0xD6, 0x10, 0xAD, 0x2F, 0x1A, 0x65,
|
||||
0x2A, 0xC5, 0xD4, 0x1A, 0xAA, 0xAC, 0x35, 0x83, 0x44, 0x86, 0xE6, 0x59, 0x7F, 0xF2, 0xE4, 0xC8,
|
||||
0xAD, 0x1D, 0x21, 0x6F, 0x88, 0x97, 0x95, 0x8B, 0x73, 0x2F, 0xF6, 0x42, 0x69, 0x72, 0x54, 0x5E,
|
||||
0xF9, 0x6A, 0x99, 0xB0, 0x20, 0x60, 0xD7, 0x25, 0x4F, 0x37, 0xBA, 0xAA, 0xFB, 0xDD, 0x05, 0xF6,
|
||||
0x32, 0x9A, 0x06, 0xA4, 0xBE, 0xC8, 0xDA, 0xC6, 0x4E, 0x08, 0x31, 0xBB, 0xC5, 0x04, 0x1B, 0x3D,
|
||||
0x23, 0xFF, 0xF7, 0xB4, 0xF5, 0x43, 0x03, 0x77, 0x11, 0xB1, 0xD6, 0xB0, 0x5E, 0x47, 0xDE, 0xD5,
|
||||
0x1D, 0x83, 0x2B, 0x5D, 0xEE, 0x82, 0x13, 0x9D, 0xCA, 0xCC, 0xD1, 0x65, 0xAF, 0xAD, 0x9D, 0x35,
|
||||
0x12, 0x24, 0xF7, 0x35, 0x4A, 0xE3, 0xE8, 0x8E, 0x0C, 0x66, 0x2E, 0x79, 0x5A, 0x38, 0xCB, 0xE7,
|
||||
0xE1, 0x65, 0x34, 0xBE, 0xE4, 0x6C, 0xFE, 0x81, 0xF2, 0xD9, 0x09, 0x4D, 0x7C, 0x16, 0x71, 0x1A,
|
||||
0xA5, 0xA2, 0x06, 0xBD, 0x4A, 0xE3, 0xCF, 0x1E, 0x4F, 0xE3, 0x66, 0x66, 0x17, 0xF1, 0x2B, 0x7B,
|
||||
0x38, 0xF1, 0xC2, 0xB9, 0x18, 0xAC, 0x40, 0xE4, 0xAD, 0x0B, 0x6E, 0xDA, 0xBB, 0x2E, 0x58, 0x71,
|
||||
0x31, 0x45, 0x47, 0x69, 0x42, 0x2E, 0x79, 0xEC, 0x65, 0x37, 0xC0, 0x99, 0x58, 0x7A, 0x43, 0x50,
|
||||
0x06, 0x36, 0xDB, 0x1B, 0x61, 0x5E, 0x5E, 0x97, 0x7F, 0x8A, 0x59, 0x3A, 0x6F, 0x0F, 0xBE, 0x66,
|
||||
0xAC, 0x31, 0x9E, 0xDC, 0xBA, 0x2A, 0x28, 0x67, 0x57, 0x39, 0xC1, 0x6A, 0xEB, 0x2A, 0x90, 0xD7,
|
||||
0xD1, 0xB8, 0x13, 0x62, 0x61, 0x5B, 0x05, 0x50, 0x68, 0x29, 0xF2, 0x47, 0x2A, 0xD4, 0x1F, 0x69,
|
||||
0x63, 0xA8, 0xF3, 0x56, 0x38, 0x8C, 0x62, 0x3A, 0x9D, 0x2E, 0x4B, 0x4F, 0xA7, 0xC3, 0xE8, 0x76,
|
||||
0x9E, 0x55, 0x15, 0xCF, 0x9F, 0xD5, 0x6B, 0x49, 0xDB, 0x45, 0xE2, 0xC6, 0xD5, 0xFD, 0xD4, 0x7B,
|
||||
0xE9, 0xEE, 0xBF, 0x95, 0x16, 0x39, 0x23, 0xB2, 0xB3, 0xD0, 0x60, 0xA9, 0xC7, 0x59, 0x7C, 0x9A,
|
||||
0x46, 0xBE, 0x20, 0x2A, 0x3F, 0x4D, 0xA4, 0x50, 0xC9, 0xBC, 0x16, 0x48, 0xEB, 0xAE, 0x5A, 0x3A,
|
||||
0xE7, 0xF0, 0xBF, 0x09, 0x06, 0x82, 0x15, 0xE1, 0x96, 0x2D, 0xDD, 0xDE, 0x1F, 0x5B, 0xDE, 0x1F,
|
||||
0x57, 0x78, 0x5F, 0x90, 0xA9, 0x18, 0xCD, 0x07, 0x3A, 0xE6, 0x33, 0x11, 0x27, 0x85, 0xD5, 0x4D,
|
||||
0x77, 0x01, 0x94, 0x25, 0x43, 0x89, 0xD0, 0x2C, 0x27, 0x75, 0x08, 0x9A, 0xE4, 0x99, 0x3E, 0xCD,
|
||||
0xBC, 0x97, 0x35, 0xAB, 0xDE, 0xD8, 0x11, 0x26, 0x14, 0x8F, 0x50, 0xE4, 0x9C, 0x34, 0x23, 0xE5,
|
||||
0x76, 0x65, 0xF0, 0xD6, 0x9A, 0xAB, 0x04, 0xE9, 0x4A, 0x76, 0x9B, 0x1C, 0xFB, 0x1D, 0x8B, 0x6F,
|
||||
0xED, 0x45, 0x09, 0xB6, 0x5B, 0x94, 0x99, 0xE4, 0x3F, 0x9F, 0x31, 0xCE, 0xF6, 0xB8, 0x30, 0x69,
|
||||
0x20, 0x24, 0xF8, 0x64, 0x42, 0x6F, 0x86, 0xFF, 0xFD, 0xF5, 0xF7, 0xBF, 0x7F, 0xFE, 0x53, 0x0D,
|
||||
0xB5, 0x66, 0xD8, 0xC7, 0xEC, 0xD7, 0x78, 0xFA, 0xA7, 0xFC, 0x4B, 0xC9, 0x79, 0x11, 0x72, 0x46,
|
||||
0xA2, 0x44, 0xC6, 0xEA, 0xF6, 0xF8, 0xBA, 0xE9, 0x6C, 0x53, 0xE1, 0x52, 0xA3, 0xB7, 0x24, 0xE2,
|
||||
0xD7, 0x12, 0x8D, 0x86, 0x6D, 0x42, 0xD3, 0x04, 0x4E, 0x21, 0x1A, 0x85, 0xBC, 0x45, 0xA6, 0xE5,
|
||||
0x18, 0x36, 0x04, 0x3B, 0xCA, 0xC6, 0x2A, 0x8B, 0x5A, 0x36, 0x6A, 0xD9, 0xA8, 0x65, 0xE3, 0x21,
|
||||
0xC9, 0x46, 0xD0, 0xE6, 0x99, 0xF5, 0x65, 0xA3, 0x22, 0x78, 0x53, 0xD9, 0xA8, 0x80, 0xD0, 0xB2,
|
||||
0x71, 0x6B, 0xD9, 0x98, 0x64, 0xB3, 0x7F, 0x41, 0x7C, 0xC1, 0xCF, 0xF7, 0x58, 0xA3, 0xE1, 0xF7,
|
||||
0x5A, 0xA3, 0xF7, 0x2F, 0xB9, 0x12, 0x41, 0x58, 0xFB, 0xCE, 0xE7, 0x43, 0x0B, 0xD7, 0x07, 0x50,
|
||||
0x3A, 0x10, 0x19, 0xB6, 0x6B, 0x1A, 0x0E, 0xB6, 0x4A, 0xA5, 0x03, 0x0C, 0x80, 0xC4, 0x7F, 0x26,
|
||||
0xB0, 0x76, 0x54, 0x3A, 0x50, 0x2B, 0x1D, 0xAD, 0x74, 0xB4, 0xD2, 0x39, 0x40, 0xA5, 0x03, 0x77,
|
||||
0x51, 0x3A, 0x8A, 0xE0, 0x4D, 0x95, 0x8E, 0x02, 0x42, 0x2B, 0x9D, 0xAD, 0x95, 0xCE, 0x94, 0x86,
|
||||
0xA2, 0xBE, 0x5F, 0x30, 0x2E, 0xB8, 0x79, 0x7F, 0xA5, 0xB1, 0xDE, 0x4B, 0x3E, 0xD1, 0xDE, 0x55,
|
||||
0xC2, 0x02, 0x41, 0xD5, 0x39, 0x4B, 0x54, 0xA7, 0x98, 0x4D, 0xA7, 0x15, 0x50, 0xE7, 0x94, 0xFB,
|
||||
0xB3, 0xC2, 0xB5, 0xE4, 0x18, 0x20, 0xA1, 0xB4, 0xED, 0xEB, 0x81, 0xC9, 0x7C, 0xDB, 0x61, 0x5E,
|
||||
0x79, 0x89, 0x41, 0x20, 0x75, 0x6B, 0x34, 0x2E, 0xAE, 0x61, 0x5E, 0x0B, 0x4A, 0x35, 0xA8, 0xA6,
|
||||
0x75, 0x05, 0xD0, 0x47, 0xEF, 0x7A, 0xC5, 0x90, 0x9A, 0xD6, 0x75, 0x80, 0x54, 0x03, 0x6A, 0x18,
|
||||
0xEF, 0x5C, 0x06, 0x23, 0x1A, 0x76, 0xCD, 0x51, 0xC3, 0xBC, 0x16, 0x54, 0x27, 0x88, 0xD6, 0x6A,
|
||||
0xA5, 0x56, 0x03, 0x36, 0x86, 0x00, 0x3A, 0x0E, 0xC4, 0x95, 0x56, 0x03, 0xAE, 0x8B, 0xA0, 0x0B,
|
||||
0x5C, 0xBC, 0xA3, 0x56, 0x43, 0x5A, 0xAB, 0x69, 0xAD, 0xA6, 0xB5, 0xDA, 0x01, 0x6A, 0x35, 0xD4,
|
||||
0xE6, 0x99, 0xF5, 0xB5, 0x9A, 0x22, 0x78, 0x53, 0xAD, 0xA6, 0x80, 0xD0, 0x5A, 0x6D, 0x6B, 0xAD,
|
||||
0xF6, 0x85, 0xB1, 0x70, 0xAF, 0x67, 0x99, 0x5E, 0x70, 0x46, 0xA2, 0x29, 0x9F, 0x0D, 0x4D, 0x67,
|
||||
0x79, 0x4E, 0xB8, 0x68, 0x54, 0x46, 0xD1, 0xE4, 0x7D, 0x92, 0x9D, 0xE6, 0x79, 0xC1, 0xA9, 0xE8,
|
||||
0x8D, 0xC5, 0xB5, 0xB3, 0xBE, 0x86, 0x41, 0xD7, 0xE1, 0xB2, 0x0E, 0x03, 0x2C, 0x2A, 0x2F, 0xC2,
|
||||
0xE5, 0x13, 0x45, 0x36, 0x46, 0x36, 0x74, 0x45, 0x6D, 0xB6, 0xDC, 0x1D, 0xCB, 0xB0, 0xA9, 0xCB,
|
||||
0xB0, 0x2E, 0xC3, 0xBA, 0x0C, 0x1F, 0x60, 0x19, 0x36, 0x77, 0x29, 0xC3, 0x8A, 0xE0, 0x4D, 0xCB,
|
||||
0xB0, 0x02, 0x42, 0x97, 0x61, 0xFD, 0x4C, 0x91, 0x7E, 0xA6, 0xE8, 0xBE, 0x64, 0xC6, 0x06, 0x8B,
|
||||
0xF2, 0x11, 0x3D, 0x53, 0xB4, 0x48, 0xBC, 0x3E, 0xAF, 0xEC, 0x4C, 0x27, 0xDC, 0x2E, 0x9D, 0x0F,
|
||||
0x73, 0x00, 0xAD, 0x13, 0x7A, 0x77, 0x42, 0xD1, 0xB6, 0x09, 0xFD, 0xF6, 0x0F, 0xA0, 0x37, 0x98,
|
||||
0x45, 0x73, 0xBB, 0x59, 0xD4, 0xA7, 0x15, 0xFA, 0xB4, 0x42, 0x9F, 0x56, 0x1C, 0xF2, 0x8D, 0x6D,
|
||||
0x6D, 0x77, 0x63, 0xEB, 0xAD, 0xAD, 0x6F, 0x62, 0x6B, 0x0B, 0xBA, 0xC8, 0x40, 0xC0, 0xAA, 0x7E,
|
||||
0x59, 0x0E, 0x59, 0x06, 0x84, 0x06, 0xB0, 0xEC, 0x5D, 0x7F, 0x5D, 0xAE, 0x5A, 0x55, 0x7A, 0x6B,
|
||||
0x4B, 0x6F, 0x6D, 0xE9, 0xAD, 0xAD, 0x43, 0xDA, 0xDA, 0xB2, 0xDA, 0x34, 0xB3, 0xFE, 0xD6, 0x96,
|
||||
0x22, 0x78, 0xD3, 0xAD, 0x2D, 0x05, 0x84, 0xDE, 0xDA, 0xDA, 0x7A, 0x6B, 0xCB, 0x4F, 0xC5, 0xF7,
|
||||
0x94, 0xF0, 0x84, 0xC6, 0xBF, 0x78, 0xE1, 0x1E, 0x05, 0xF6, 0xF7, 0x58, 0x1A, 0x2D, 0xCB, 0x00,
|
||||
0x08, 0x1B, 0x66, 0xF9, 0xF4, 0x05, 0x76, 0x6D, 0x0B, 0x00, 0x6C, 0xB8, 0xD6, 0xAE, 0x4F, 0x5F,
|
||||
0xD8, 0xBA, 0x36, 0xEA, 0xDA, 0xA8, 0x6B, 0xE3, 0xBE, 0x6B, 0xE3, 0xFE, 0x9E, 0xA1, 0x87, 0x86,
|
||||
0x6B, 0x40, 0x21, 0x9A, 0x41, 0xC1, 0x0C, 0x8E, 0x85, 0x50, 0x76, 0x48, 0x6C, 0x19, 0xBB, 0x32,
|
||||
0x03, 0xD6, 0xCC, 0xA0, 0x99, 0x41, 0x33, 0xC3, 0x01, 0xAA, 0x66, 0xBB, 0xAD, 0x40, 0xD6, 0x57,
|
||||
0xCD, 0xB8, 0x1D, 0xBC, 0xA9, 0x6A, 0x56, 0x40, 0x1C, 0x94, 0x6A, 0x0E, 0xD3, 0x80, 0xD3, 0x79,
|
||||
0x40, 0x4E, 0xCA, 0xF7, 0x07, 0xAD, 0xA3, 0x9D, 0x95, 0x68, 0x45, 0x7E, 0x81, 0xA1, 0x02, 0x58,
|
||||
0xAD, 0x16, 0xF5, 0xC1, 0xB2, 0x3E, 0x58, 0xD6, 0x07, 0xCB, 0xF7, 0x72, 0xB0, 0xFC, 0xCD, 0x1D,
|
||||
0x27, 0x3E, 0xC0, 0xF7, 0x4B, 0xE8, 0x22, 0xD3, 0x71, 0xA1, 0x83, 0xCB, 0x77, 0x4E, 0x38, 0x26,
|
||||
0x30, 0x91, 0x05, 0x91, 0x01, 0x9C, 0x1D, 0x55, 0x64, 0xB5, 0x5F, 0xAE, 0x55, 0xA4, 0x56, 0x91,
|
||||
0x5A, 0x45, 0x3E, 0xBE, 0xEF, 0x97, 0x08, 0x1A, 0x26, 0x30, 0x90, 0xEB, 0x56, 0x1B, 0x4F, 0xD0,
|
||||
0x31, 0x91, 0x0B, 0xB1, 0xBB, 0x2B, 0x31, 0xB8, 0x9A, 0x18, 0x34, 0x31, 0x68, 0x62, 0x78, 0xB4,
|
||||
0xC4, 0x00, 0xB1, 0x6D, 0x02, 0x17, 0xC3, 0xEA, 0xE5, 0x0D, 0xD8, 0x74, 0x21, 0x04, 0x8E, 0x68,
|
||||
0xD9, 0xF5, 0xB8, 0x76, 0xF1, 0x7D, 0x4B, 0x53, 0x83, 0xA6, 0x06, 0x4D, 0x0D, 0x8F, 0x90, 0x1A,
|
||||
0x10, 0x14, 0xDF, 0x28, 0x0C, 0xCB, 0x2E, 0xF7, 0xA4, 0xB1, 0x61, 0x59, 0xAE, 0xEB, 0xD8, 0xB6,
|
||||
0x85, 0x76, 0xA5, 0x06, 0xFD, 0x0A, 0x3B, 0x4D, 0x0D, 0x9A, 0x1A, 0x1E, 0x2F, 0x35, 0x08, 0xC5,
|
||||
0x80, 0x4D, 0x0B, 0x98, 0x4E, 0xF5, 0xCA, 0x27, 0x1B, 0x58, 0x8E, 0xED, 0x42, 0xE4, 0xEC, 0xFC,
|
||||
0x72, 0x4B, 0xFD, 0xCE, 0x27, 0x4D, 0x0D, 0x9A, 0x1A, 0x1E, 0x31, 0x35, 0x60, 0xC7, 0x72, 0x30,
|
||||
0x06, 0xD5, 0x1E, 0x24, 0xB6, 0x4C, 0x64, 0xDB, 0x0E, 0xC2, 0xF6, 0xAE, 0x5B, 0x0D, 0x40, 0xBF,
|
||||
0x62, 0x44, 0x53, 0x83, 0xA6, 0x86, 0xFB, 0xA7, 0x86, 0x41, 0x7F, 0xF9, 0x67, 0x69, 0x06, 0xFD,
|
||||
0xE5, 0x9F, 0x7A, 0x1A, 0x64, 0x7F, 0x2E, 0x6A, 0xF8, 0xE4, 0x7F, 0x50, 0x4B, 0x07, 0x08, 0x9F,
|
||||
0x7E, 0x60, 0xC2, 0x2B, 0x07, 0x00, 0x00, 0x7E, 0x6A, 0x00, 0x00, 0x50, 0x4B, 0x01, 0x02, 0x14,
|
||||
0x00, 0x14, 0x00, 0x08, 0x08, 0x08, 0x00, 0x8A, 0x81, 0x3E, 0x56, 0xF2, 0xB2, 0xDF, 0xE7, 0xD1,
|
||||
0x06, 0x00, 0x00, 0x66, 0x4D, 0x00, 0x00, 0x11, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x77, 0x70, 0x6D, 0x7A, 0x2F, 0x74, 0x65,
|
||||
0x6D, 0x70, 0x6C, 0x61, 0x74, 0x65, 0x2E, 0x6B, 0x6D, 0x6C, 0x50, 0x4B, 0x01, 0x02, 0x14, 0x00,
|
||||
0x14, 0x00, 0x08, 0x08, 0x08, 0x00, 0x8A, 0x81, 0x3E, 0x56, 0x9F, 0x7E, 0x60, 0xC2, 0x2B, 0x07,
|
||||
0x00, 0x00, 0x7E, 0x6A, 0x00, 0x00, 0x12, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x10, 0x07, 0x00, 0x00, 0x77, 0x70, 0x6D, 0x7A, 0x2F, 0x77, 0x61, 0x79,
|
||||
0x6C, 0x69, 0x6E, 0x65, 0x73, 0x2E, 0x77, 0x70, 0x6D, 0x6C, 0x50, 0x4B, 0x05, 0x06, 0x00, 0x00,
|
||||
0x00, 0x00, 0x02, 0x00, 0x02, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x7B, 0x0E, 0x00, 0x00, 0x00, 0x00
|
||||
};
|
||||
|
||||
#endif /* __waypoint_v3_test_file_kmz_h_included */
|
||||
|
||||
@ -23,8 +23,6 @@
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
|
||||
#include "test_widget_speaker.h"
|
||||
#include "dji_logger.h"
|
||||
#include <stdlib.h>
|
||||
@ -92,6 +90,7 @@ static T_DjiReturnCode ReceiveTtsData(E_DjiWidgetTransmitDataEvent event,
|
||||
uint32_t offset, uint8_t *buf, uint16_t size);
|
||||
static T_DjiReturnCode ReceiveAudioData(E_DjiWidgetTransmitDataEvent event,
|
||||
uint32_t offset, uint8_t *buf, uint16_t size);
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
static void *DjiTest_WidgetSpeakerTask(void *arg);
|
||||
static uint32_t DjiTest_GetVoicePlayProcessId(void);
|
||||
static uint32_t DjiTest_KillVoicePlayProcess(uint32_t pid);
|
||||
@ -99,6 +98,7 @@ static T_DjiReturnCode DjiTest_DecodeAudioData(void);
|
||||
static T_DjiReturnCode DjiTest_PlayAudioData(void);
|
||||
static T_DjiReturnCode DjiTest_PlayTtsData(void);
|
||||
static T_DjiReturnCode DjiTest_CheckFileMd5Sum(const char *path, uint8_t *buf, uint16_t size);
|
||||
#endif
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
T_DjiReturnCode DjiTest_WidgetSpeakerStartService(void)
|
||||
@ -149,17 +149,20 @@ T_DjiReturnCode DjiTest_WidgetSpeakerStartService(void)
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
if (osalHandler->TaskCreate("user_widget_speaker_task", DjiTest_WidgetSpeakerTask, WIDGET_SPEAKER_TASK_STACK_SIZE,
|
||||
NULL,
|
||||
&s_widgetSpeakerTestThread) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Dji widget speaker test task create error.");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
}
|
||||
#endif
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
static uint32_t DjiTest_GetVoicePlayProcessId(void)
|
||||
{
|
||||
FILE *fp;
|
||||
@ -217,21 +220,21 @@ static T_DjiReturnCode DjiTest_DecodeAudioData(void)
|
||||
/*! Attention: you can use "ffmpeg -i xxx.mp3 -ar 16000 -ac 1 out.wav" and use opus-tools to generate opus file for test */
|
||||
fin = fopen(WIDGET_SPEAKER_AUDIO_OPUS_FILE_NAME, "r");
|
||||
if (fin == NULL) {
|
||||
fprintf(stderr, "failed to open input file: %s\n", strerror(errno));
|
||||
return EXIT_FAILURE;
|
||||
}
|
||||
|
||||
/* Create a new decoder state. */
|
||||
decoder = opus_decoder_create(WIDGET_SPEAKER_AUDIO_OPUS_SAMPLE_RATE, WIDGET_SPEAKER_AUDIO_OPUS_CHANNELS, &err);
|
||||
if (err < 0) {
|
||||
fprintf(stderr, "failed to create decoder: %s\n", opus_strerror(err));
|
||||
USER_LOG_ERROR("failed to open input file: %s\n", strerror(errno));
|
||||
return EXIT_FAILURE;
|
||||
}
|
||||
|
||||
fout = fopen(WIDGET_SPEAKER_AUDIO_PCM_FILE_NAME, "w");
|
||||
if (fout == NULL) {
|
||||
fprintf(stderr, "failed to open output file: %s\n", strerror(errno));
|
||||
return EXIT_FAILURE;
|
||||
USER_LOG_ERROR("failed to open output file: %s\n", strerror(errno));
|
||||
goto open_pcm_audio_failed;
|
||||
}
|
||||
|
||||
/* Create a new decoder state. */
|
||||
decoder = opus_decoder_create(WIDGET_SPEAKER_AUDIO_OPUS_SAMPLE_RATE, WIDGET_SPEAKER_AUDIO_OPUS_CHANNELS, &err);
|
||||
if (err < 0) {
|
||||
USER_LOG_ERROR("failed to create decoder: %s\n", opus_strerror(err));
|
||||
goto create_decoder_failed;
|
||||
}
|
||||
|
||||
while (1) {
|
||||
@ -251,8 +254,8 @@ static T_DjiReturnCode DjiTest_DecodeAudioData(void)
|
||||
the frame size returned. */
|
||||
frame_size = opus_decode(decoder, cbits, nbBytes, out, WIDGET_SPEAKER_AUDIO_OPUS_MAX_FRAME_SIZE, 0);
|
||||
if (frame_size < 0) {
|
||||
fprintf(stderr, "decoder failed: %s\n", opus_strerror(frame_size));
|
||||
return EXIT_FAILURE;
|
||||
USER_LOG_ERROR("decoder failed: %s\n", opus_strerror(frame_size));
|
||||
goto decode_data_failed;
|
||||
}
|
||||
|
||||
USER_LOG_DEBUG("decode data to file: %d\r\n", frame_size * WIDGET_SPEAKER_AUDIO_OPUS_CHANNELS);
|
||||
@ -265,16 +268,18 @@ static T_DjiReturnCode DjiTest_DecodeAudioData(void)
|
||||
fwrite(pcm_bytes, sizeof(short), frame_size * WIDGET_SPEAKER_AUDIO_OPUS_CHANNELS, fout);
|
||||
}
|
||||
|
||||
/*Destroy the encoder state*/
|
||||
opus_decoder_destroy(decoder);
|
||||
fclose(fin);
|
||||
fclose(fout);
|
||||
|
||||
USER_LOG_INFO("Decode Finished...");
|
||||
s_isDecodeFinished = true;
|
||||
|
||||
decode_data_failed:
|
||||
opus_decoder_destroy(decoder);
|
||||
create_decoder_failed:
|
||||
fclose(fout);
|
||||
open_pcm_audio_failed:
|
||||
fclose(fin);
|
||||
#endif
|
||||
return EXIT_SUCCESS;
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiTest_PlayAudioData(void)
|
||||
@ -311,17 +316,19 @@ static T_DjiReturnCode DjiTest_PlayTtsData(void)
|
||||
} else {
|
||||
txtFile = fopen(WIDGET_SPEAKER_TTS_FILE_NAME, "r");
|
||||
if (txtFile == NULL) {
|
||||
fprintf(stderr, "failed to open input file: %s\n", strerror(errno));
|
||||
USER_LOG_ERROR("failed to open input file: %s\n", strerror(errno));
|
||||
return EXIT_FAILURE;
|
||||
}
|
||||
|
||||
readLen = fread(data, 1, WIDGET_SPEAKER_TTS_FILE_MAX_SIZE, txtFile);
|
||||
readLen = fread(data, 1, WIDGET_SPEAKER_TTS_FILE_MAX_SIZE - 1, txtFile);
|
||||
if (readLen <= 0) {
|
||||
USER_LOG_ERROR("Read tts file failed, error code: %d", readLen);
|
||||
fclose(txtFile);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_NOT_FOUND;
|
||||
}
|
||||
|
||||
data[readLen] = '\0';
|
||||
|
||||
fclose(txtFile);
|
||||
|
||||
USER_LOG_INFO("Read tts file success, len: %d", readLen);
|
||||
@ -358,7 +365,7 @@ static T_DjiReturnCode DjiTest_CheckFileMd5Sum(const char *path, uint8_t *buf, u
|
||||
uint16_t readLen;
|
||||
T_DjiReturnCode returnCode;
|
||||
uint8_t readBuf[1024];
|
||||
uint8_t md5Sum[16];
|
||||
uint8_t md5Sum[16] = {0};
|
||||
FILE *file = NULL;;
|
||||
|
||||
UtilMd5_Init(&md5Ctx);
|
||||
@ -400,6 +407,7 @@ static T_DjiReturnCode DjiTest_CheckFileMd5Sum(const char *path, uint8_t *buf, u
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
#endif
|
||||
|
||||
static void SetSpeakerState(E_DjiWidgetSpeakerState speakerState)
|
||||
{
|
||||
@ -492,10 +500,12 @@ static T_DjiReturnCode StartPlay(void)
|
||||
uint32_t pid;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
pid = DjiTest_GetVoicePlayProcessId();
|
||||
if (pid != 0) {
|
||||
DjiTest_KillVoicePlayProcess(pid);
|
||||
}
|
||||
#endif
|
||||
|
||||
osalHandler->TaskSleepMs(5);
|
||||
USER_LOG_INFO("Start widget speaker play");
|
||||
@ -519,10 +529,12 @@ static T_DjiReturnCode StopPlay(void)
|
||||
USER_LOG_INFO("Stop widget speaker play");
|
||||
s_speakerState.state = DJI_WIDGET_SPEAKER_STATE_IDEL;
|
||||
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
pid = DjiTest_GetVoicePlayProcessId();
|
||||
if (pid != 0) {
|
||||
DjiTest_KillVoicePlayProcess(pid);
|
||||
}
|
||||
#endif
|
||||
|
||||
returnCode = osalHandler->MutexUnlock(s_speakerMutex);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -588,15 +600,18 @@ static T_DjiReturnCode ReceiveTtsData(E_DjiWidgetTransmitDataEvent event,
|
||||
|
||||
if (event == DJI_WIDGET_TRANSMIT_DATA_EVENT_START) {
|
||||
USER_LOG_INFO("Create tts file.");
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
s_ttsFile = fopen(WIDGET_SPEAKER_TTS_FILE_NAME, "wb");
|
||||
if (s_ttsFile == NULL) {
|
||||
USER_LOG_ERROR("Open tts file error.");
|
||||
}
|
||||
#endif
|
||||
if (s_speakerState.state != DJI_WIDGET_SPEAKER_STATE_PLAYING) {
|
||||
SetSpeakerState(DJI_WIDGET_SPEAKER_STATE_TRANSMITTING);
|
||||
}
|
||||
} else if (event == DJI_WIDGET_TRANSMIT_DATA_EVENT_TRANSMIT) {
|
||||
USER_LOG_INFO("Transmit tts file, offset: %d, size: %d", offset, size);
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
if (s_ttsFile != NULL) {
|
||||
fseek(s_ttsFile, offset, SEEK_SET);
|
||||
writeLen = fwrite(buf, 1, size, s_ttsFile);
|
||||
@ -604,11 +619,13 @@ static T_DjiReturnCode ReceiveTtsData(E_DjiWidgetTransmitDataEvent event,
|
||||
USER_LOG_ERROR("Write tts file error %d", writeLen);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
if (s_speakerState.state != DJI_WIDGET_SPEAKER_STATE_PLAYING) {
|
||||
SetSpeakerState(DJI_WIDGET_SPEAKER_STATE_TRANSMITTING);
|
||||
}
|
||||
} else if (event == DJI_WIDGET_TRANSMIT_DATA_EVENT_FINISH) {
|
||||
USER_LOG_INFO("Close tts file.");
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
if (s_ttsFile != NULL) {
|
||||
fclose(s_ttsFile);
|
||||
}
|
||||
@ -617,6 +634,7 @@ static T_DjiReturnCode ReceiveTtsData(E_DjiWidgetTransmitDataEvent event,
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("File md5 sum check failed");
|
||||
}
|
||||
#endif
|
||||
if (s_speakerState.state != DJI_WIDGET_SPEAKER_STATE_PLAYING) {
|
||||
SetSpeakerState(DJI_WIDGET_SPEAKER_STATE_IDEL);
|
||||
}
|
||||
@ -634,6 +652,7 @@ static T_DjiReturnCode ReceiveAudioData(E_DjiWidgetTransmitDataEvent event,
|
||||
|
||||
if (event == DJI_WIDGET_TRANSMIT_DATA_EVENT_START) {
|
||||
s_isDecodeFinished = false;
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
USER_LOG_INFO("Create voice file.");
|
||||
s_audioFile = fopen(WIDGET_SPEAKER_AUDIO_OPUS_FILE_NAME, "wb");
|
||||
if (s_audioFile == NULL) {
|
||||
@ -642,6 +661,7 @@ static T_DjiReturnCode ReceiveAudioData(E_DjiWidgetTransmitDataEvent event,
|
||||
if (s_speakerState.state != DJI_WIDGET_SPEAKER_STATE_PLAYING) {
|
||||
SetSpeakerState(DJI_WIDGET_SPEAKER_STATE_TRANSMITTING);
|
||||
}
|
||||
#endif
|
||||
|
||||
memcpy(&transDataContent, buf, size);
|
||||
s_decodeBitrate = transDataContent.transDataStartContent.fileDecodeBitrate;
|
||||
@ -649,6 +669,7 @@ static T_DjiReturnCode ReceiveAudioData(E_DjiWidgetTransmitDataEvent event,
|
||||
transDataContent.transDataStartContent.fileDecodeBitrate);
|
||||
} else if (event == DJI_WIDGET_TRANSMIT_DATA_EVENT_TRANSMIT) {
|
||||
USER_LOG_INFO("Transmit voice file, offset: %d, size: %d", offset, size);
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
if (s_audioFile != NULL) {
|
||||
fseek(s_audioFile, offset, SEEK_SET);
|
||||
writeLen = fwrite(buf, 1, size, s_audioFile);
|
||||
@ -656,6 +677,7 @@ static T_DjiReturnCode ReceiveAudioData(E_DjiWidgetTransmitDataEvent event,
|
||||
USER_LOG_ERROR("Write tts file error %d", writeLen);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
if (s_speakerState.state != DJI_WIDGET_SPEAKER_STATE_PLAYING) {
|
||||
SetSpeakerState(DJI_WIDGET_SPEAKER_STATE_TRANSMITTING);
|
||||
}
|
||||
@ -665,21 +687,25 @@ static T_DjiReturnCode ReceiveAudioData(E_DjiWidgetTransmitDataEvent event,
|
||||
fclose(s_audioFile);
|
||||
}
|
||||
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
returnCode = DjiTest_CheckFileMd5Sum(WIDGET_SPEAKER_AUDIO_OPUS_FILE_NAME, buf, size);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("File md5 sum check failed");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
#endif
|
||||
if (s_speakerState.state != DJI_WIDGET_SPEAKER_STATE_PLAYING) {
|
||||
SetSpeakerState(DJI_WIDGET_SPEAKER_STATE_IDEL);
|
||||
}
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
DjiTest_DecodeAudioData();
|
||||
#endif
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
#ifndef __CC_ARM
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wmissing-noreturn"
|
||||
@ -752,7 +778,6 @@ static void *DjiTest_WidgetSpeakerTask(void *arg)
|
||||
#ifndef __CC_ARM
|
||||
#pragma GCC diagnostic pop
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
|
||||
@ -34,7 +34,6 @@
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
T_DjiReturnCode DjiTest_WidgetSpeakerStartService(void);
|
||||
@ -43,8 +42,6 @@ T_DjiReturnCode DjiTest_WidgetSpeakerStartService(void);
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -45,6 +45,8 @@
|
||||
#include <payload_collaboration/test_payload_collaboration.h>
|
||||
#include <waypoint_v3/test_waypoint_v3.h>
|
||||
#include "dji_sdk_config.h"
|
||||
#include "hms/hms_text_c/en/hms_text_config_json.h"
|
||||
#include "dji_hms.h"
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define WIDGET_DIR_PATH_LEN_MAX (256)
|
||||
@ -83,10 +85,27 @@ typedef enum {
|
||||
E_DJI_SAMPLE_INDEX_CAMMGR_INTERVAL_PHOTO = 25,
|
||||
E_DJI_SAMPLE_INDEX_CAMMGR_RECORDER_VIDEO = 26,
|
||||
E_DJI_SAMPLE_INDEX_CAMMGR_MEDIA_DOWNLOAD = 27,
|
||||
E_DJI_SAMPLE_INDEX_CAMMGR_THERMOMETRY = 28,
|
||||
|
||||
E_DJI_SAMPLE_INDEX_UNKNOWN = 0xFF,
|
||||
} E_DjiExtensionPortSampleIndex;
|
||||
|
||||
typedef enum {
|
||||
E_DJI_HMS_ERROR_CODE_INDEX1 = 0,
|
||||
E_DJI_HMS_ERROR_CODE_INDEX2,
|
||||
E_DJI_HMS_ERROR_CODE_INDEX3,
|
||||
E_DJI_HMS_ERROR_CODE_INDEX4,
|
||||
E_DJI_HMS_ERROR_CODE_INDEX5,
|
||||
}E_DjiExtensionPortHmsErrorCodeIndex;
|
||||
|
||||
typedef enum {
|
||||
E_DJI_HMS_ERROR_LEVEL_INDEX1 = 0,
|
||||
E_DJI_HMS_ERROR_LEVEL_INDEX2,
|
||||
E_DJI_HMS_ERROR_LEVEL_INDEX3,
|
||||
E_DJI_HMS_ERROR_LEVEL_INDEX4,
|
||||
E_DJI_HMS_ERROR_LEVEL_INDEX5,
|
||||
}E_DjiExtensionPortHmsErrorLevelIndex;
|
||||
|
||||
typedef struct {
|
||||
bool valid;
|
||||
char content[WIDGET_LOG_STRING_MAX_SIZE];
|
||||
@ -105,6 +124,10 @@ static T_DjiReturnCode DjiTestWidget_TriggerChangeAlias(void);
|
||||
static T_DjiTaskHandle s_widgetTestThread;
|
||||
static T_DjiTaskHandle s_widgetInteractionTestThread;
|
||||
static E_DjiExtensionPortSampleIndex s_extensionPortSampleIndex = E_DJI_SAMPLE_INDEX_FC_SUBSCRIPTION;
|
||||
static E_DjiExtensionPortHmsErrorCodeIndex s_extensionPortErrcodeIndex = E_DJI_HMS_ERROR_CODE_INDEX1;
|
||||
static E_DjiExtensionPortHmsErrorLevelIndex s_extensionPortErrLevelIndex = E_DJI_HMS_ERROR_LEVEL_INDEX1;
|
||||
static bool s_isInjectErrcode = false;
|
||||
static bool s_isEliminateErrcode = false;
|
||||
static bool s_isallowRunFlightControlSample = false;
|
||||
static bool s_isSampleStart = false;
|
||||
static E_DjiMountPosition s_mountPosition = DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1;
|
||||
@ -124,6 +147,10 @@ static const T_DjiWidgetHandlerListItem s_widgetHandlerList[] = {
|
||||
{8, DJI_WIDGET_TYPE_LIST, DjiTestWidget_SetWidgetValue, DjiTestWidget_GetWidgetValue, NULL},
|
||||
{9, DJI_WIDGET_TYPE_LIST, DjiTestWidget_SetWidgetValue, DjiTestWidget_GetWidgetValue, NULL},
|
||||
{10, DJI_WIDGET_TYPE_BUTTON, DjiTestWidget_SetWidgetValue, DjiTestWidget_GetWidgetValue, NULL},
|
||||
{11, DJI_WIDGET_TYPE_LIST, DjiTestWidget_SetWidgetValue, DjiTestWidget_GetWidgetValue, NULL},
|
||||
{12, DJI_WIDGET_TYPE_LIST, DjiTestWidget_SetWidgetValue, DjiTestWidget_GetWidgetValue, NULL},
|
||||
{13, DJI_WIDGET_TYPE_BUTTON, DjiTestWidget_SetWidgetValue, DjiTestWidget_GetWidgetValue, NULL},
|
||||
{14, DJI_WIDGET_TYPE_BUTTON, DjiTestWidget_SetWidgetValue, DjiTestWidget_GetWidgetValue, NULL},
|
||||
};
|
||||
|
||||
static const char *s_widgetTypeNameArray[] = {
|
||||
@ -334,6 +361,8 @@ static void *DjiTest_WidgetInteractionTask(void *arg)
|
||||
{
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
T_DjiReturnCode returnCode;
|
||||
uint32_t errorCode;
|
||||
E_DjiHmsErrorLevel errorLevel;
|
||||
|
||||
returnCode = DjiAircraftInfo_GetBaseInfo(&s_aircraftInfoBaseInfo);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -344,6 +373,78 @@ static void *DjiTest_WidgetInteractionTask(void *arg)
|
||||
while (1) {
|
||||
osalHandler->TaskSleepMs(100);
|
||||
|
||||
if (s_isInjectErrcode == true && s_isEliminateErrcode == false) {
|
||||
switch (s_extensionPortErrcodeIndex) {
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX1:
|
||||
errorCode = 0x1E020000;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX2:
|
||||
errorCode = 0x1E020001;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX3:
|
||||
errorCode = 0x1E020002;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX4:
|
||||
errorCode = 0x1E020003;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX5:
|
||||
errorCode = 0x1E020004;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
switch (s_extensionPortErrLevelIndex) {
|
||||
case E_DJI_HMS_ERROR_LEVEL_INDEX1:
|
||||
errorLevel = DJI_HMS_ERROR_LEVEL_NONE;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_LEVEL_INDEX2:
|
||||
errorLevel = DJI_HMS_ERROR_LEVEL_HINT;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_LEVEL_INDEX3:
|
||||
errorLevel = DJI_HMS_ERROR_LEVEL_WARN;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_LEVEL_INDEX4:
|
||||
errorLevel = DJI_HMS_ERROR_LEVEL_CRITICAL;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_LEVEL_INDEX5:
|
||||
errorLevel = DJI_HMS_ERROR_LEVEL_FATAL;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
DjiHms_InjectHmsErrorCode(errorCode, errorLevel);
|
||||
osalHandler->TaskSleepMs(500);
|
||||
s_isInjectErrcode = false;
|
||||
s_isEliminateErrcode = false;
|
||||
continue;
|
||||
}
|
||||
if (s_isEliminateErrcode == true && s_isInjectErrcode == false) {
|
||||
switch (s_extensionPortErrcodeIndex) {
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX1:
|
||||
errorCode = 0x1E020000;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX2:
|
||||
errorCode = 0x1E020001;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX3:
|
||||
errorCode = 0x1E020002;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX4:
|
||||
errorCode = 0x1E020003;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX5:
|
||||
errorCode = 0x1E020004;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
DjiHms_EliminateHmsErrorCode(errorCode);
|
||||
osalHandler->TaskSleepMs(500);
|
||||
s_isInjectErrcode = false;
|
||||
s_isEliminateErrcode = false;
|
||||
continue;
|
||||
}
|
||||
|
||||
if (s_isSampleStart != true) {
|
||||
continue;
|
||||
}
|
||||
@ -495,12 +596,15 @@ static void *DjiTest_WidgetInteractionTask(void *arg)
|
||||
DjiTest_CameraManagerRunSample(s_mountPosition,
|
||||
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_DOWNLOAD_AND_DELETE_MEDIA_FILE);
|
||||
break;
|
||||
case E_DJI_SAMPLE_INDEX_CAMMGR_THERMOMETRY:
|
||||
DjiTest_CameraManagerRunSample(s_mountPosition,
|
||||
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_THERMOMETRY);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
} else {
|
||||
USER_LOG_WARN("Can't support on payload port.");
|
||||
break;
|
||||
}
|
||||
|
||||
USER_LOG_INFO("--------------------------------------------------------------------------------------------->");
|
||||
@ -541,6 +645,28 @@ static T_DjiReturnCode DjiTestWidget_SetWidgetValue(E_DjiWidgetType widgetType,
|
||||
}
|
||||
}
|
||||
|
||||
if (widgetType == DJI_WIDGET_TYPE_LIST && index == 11) {
|
||||
s_extensionPortErrcodeIndex = value;
|
||||
}
|
||||
|
||||
if (widgetType == DJI_WIDGET_TYPE_LIST && index == 12) {
|
||||
s_extensionPortErrLevelIndex = value;
|
||||
}
|
||||
|
||||
if (widgetType == DJI_WIDGET_TYPE_BUTTON && index == 13) {
|
||||
if (value == 1) {
|
||||
s_isInjectErrcode = true;
|
||||
s_isEliminateErrcode = false;
|
||||
}
|
||||
}
|
||||
|
||||
if (widgetType == DJI_WIDGET_TYPE_BUTTON && index == 14) {
|
||||
if (value == 1) {
|
||||
s_isInjectErrcode = false;
|
||||
s_isEliminateErrcode = true;
|
||||
}
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
|
||||
@ -218,6 +218,9 @@
|
||||
},
|
||||
{
|
||||
"item_name": "28_test_cammgr-media_download"
|
||||
},
|
||||
{
|
||||
"item_name": "29_test_cammgr-thermometry"
|
||||
}
|
||||
]
|
||||
},
|
||||
@ -225,7 +228,61 @@
|
||||
"widget_index": 10,
|
||||
"widget_type": "button",
|
||||
"widget_name": "Run"
|
||||
},
|
||||
{
|
||||
"widget_index": 11,
|
||||
"widget_type": "list",
|
||||
"widget_name": "Please Select Errcode",
|
||||
"list_item": [
|
||||
{
|
||||
"item_name": "0x1E020000"
|
||||
},
|
||||
{
|
||||
"item_name": "0x1E020001"
|
||||
},
|
||||
{
|
||||
"item_name": "0x1E020002"
|
||||
},
|
||||
{
|
||||
"item_name": "0x1E020003"
|
||||
},
|
||||
{
|
||||
"item_name": "0x1E020004"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"widget_index": 12,
|
||||
"widget_type": "list",
|
||||
"widget_name": "Please Select ErrLevel",
|
||||
"list_item": [
|
||||
{
|
||||
"item_name": "Error level 0"
|
||||
},
|
||||
{
|
||||
"item_name": "Error level 1"
|
||||
},
|
||||
{
|
||||
"item_name": "Error level 2"
|
||||
},
|
||||
{
|
||||
"item_name": "Error level 3"
|
||||
},
|
||||
{
|
||||
"item_name": "Error level 4"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"widget_index": 13,
|
||||
"widget_type": "button",
|
||||
"widget_name": "Inject"
|
||||
},
|
||||
{
|
||||
"widget_index": 14,
|
||||
"widget_type": "button",
|
||||
"widget_name": "Eliminate"
|
||||
}
|
||||
]
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -218,6 +218,9 @@
|
||||
},
|
||||
{
|
||||
"item_name": "28_test_cammgr-media_download"
|
||||
},
|
||||
{
|
||||
"item_name": "29_test_cammgr-thermometry"
|
||||
}
|
||||
]
|
||||
},
|
||||
@ -225,7 +228,61 @@
|
||||
"widget_index": 10,
|
||||
"widget_type": "button",
|
||||
"widget_name": "Run"
|
||||
},
|
||||
{
|
||||
"widget_index": 11,
|
||||
"widget_type": "list",
|
||||
"widget_name": "Please Select Errcode",
|
||||
"list_item": [
|
||||
{
|
||||
"item_name": "0x1E020000"
|
||||
},
|
||||
{
|
||||
"item_name": "0x1E020001"
|
||||
},
|
||||
{
|
||||
"item_name": "0x1E020002"
|
||||
},
|
||||
{
|
||||
"item_name": "0x1E020003"
|
||||
},
|
||||
{
|
||||
"item_name": "0x1E020004"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"widget_index": 12,
|
||||
"widget_type": "list",
|
||||
"widget_name": "Please Select ErrLevel",
|
||||
"list_item": [
|
||||
{
|
||||
"item_name": "Error level0"
|
||||
},
|
||||
{
|
||||
"item_name": "Error level1"
|
||||
},
|
||||
{
|
||||
"item_name": "Error level2"
|
||||
},
|
||||
{
|
||||
"item_name": "Error level3"
|
||||
},
|
||||
{
|
||||
"item_name": "Error level4"
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"widget_index": 13,
|
||||
"widget_type": "button",
|
||||
"widget_name": "Inject"
|
||||
},
|
||||
{
|
||||
"widget_index": 14,
|
||||
"widget_type": "button",
|
||||
"widget_name": "Eliminate"
|
||||
}
|
||||
]
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -6,9 +6,9 @@
|
||||
|
||||
/* Contents of file widget_config.json */
|
||||
#define widget_config_json_fileName "widget_config.json"
|
||||
#define widget_config_json_fileSize 6000
|
||||
#define widget_config_json_fileSize 7255
|
||||
|
||||
static const uint8_t widget_config_json_fileBinaryArray[6000] = {
|
||||
static const uint8_t widget_config_json_fileBinaryArray[7255] = {
|
||||
0x7B, 0x0A, 0x20, 0x20, 0x22, 0x76, 0x65, 0x72, 0x73, 0x69, 0x6F, 0x6E, 0x22, 0x3A, 0x20, 0x7B,
|
||||
0x0A, 0x20, 0x20, 0x20, 0x20, 0x22, 0x6D, 0x61, 0x6A, 0x6F, 0x72, 0x22, 0x3A, 0x20, 0x31, 0x2C,
|
||||
0x0A, 0x20, 0x20, 0x20, 0x20, 0x22, 0x6D, 0x69, 0x6E, 0x6F, 0x72, 0x22, 0x3A, 0x20, 0x30, 0x0A,
|
||||
@ -375,15 +375,94 @@ static const uint8_t widget_config_json_fileBinaryArray[6000] = {
|
||||
0x74, 0x65, 0x6D, 0x5F, 0x6E, 0x61, 0x6D, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x32, 0x38, 0x5F, 0x74,
|
||||
0x65, 0x73, 0x74, 0x5F, 0x63, 0x61, 0x6D, 0x6D, 0x67, 0x72, 0x2D, 0x6D, 0x65, 0x64, 0x69, 0x61,
|
||||
0x5F, 0x64, 0x6F, 0x77, 0x6E, 0x6C, 0x6F, 0x61, 0x64, 0x22, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x5D,
|
||||
0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69, 0x64, 0x67, 0x65,
|
||||
0x74, 0x5F, 0x69, 0x6E, 0x64, 0x65, 0x78, 0x22, 0x3A, 0x20, 0x31, 0x30, 0x2C, 0x0A, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69, 0x64, 0x67, 0x65, 0x74, 0x5F, 0x74, 0x79,
|
||||
0x70, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x62, 0x75, 0x74, 0x74, 0x6F, 0x6E, 0x22, 0x2C, 0x0A, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69, 0x64, 0x67, 0x65, 0x74, 0x5F, 0x6E,
|
||||
0x61, 0x6D, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x52, 0x75, 0x6E, 0x22, 0x0A, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x7D, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x5D, 0x0A, 0x20, 0x20, 0x7D, 0x0A, 0x7D, 0x0A
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x22, 0x69, 0x74, 0x65, 0x6D, 0x5F, 0x6E, 0x61, 0x6D, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x32, 0x39,
|
||||
0x5F, 0x74, 0x65, 0x73, 0x74, 0x5F, 0x63, 0x61, 0x6D, 0x6D, 0x67, 0x72, 0x2D, 0x74, 0x68, 0x65,
|
||||
0x72, 0x6D, 0x6F, 0x6D, 0x65, 0x74, 0x72, 0x79, 0x22, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x7D, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x5D, 0x0A,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7B,
|
||||
0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69, 0x64, 0x67, 0x65, 0x74,
|
||||
0x5F, 0x69, 0x6E, 0x64, 0x65, 0x78, 0x22, 0x3A, 0x20, 0x31, 0x30, 0x2C, 0x0A, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69, 0x64, 0x67, 0x65, 0x74, 0x5F, 0x74, 0x79, 0x70,
|
||||
0x65, 0x22, 0x3A, 0x20, 0x22, 0x62, 0x75, 0x74, 0x74, 0x6F, 0x6E, 0x22, 0x2C, 0x0A, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69, 0x64, 0x67, 0x65, 0x74, 0x5F, 0x6E, 0x61,
|
||||
0x6D, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x52, 0x75, 0x6E, 0x22, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69, 0x64, 0x67, 0x65, 0x74, 0x5F, 0x69, 0x6E, 0x64, 0x65,
|
||||
0x78, 0x22, 0x3A, 0x20, 0x31, 0x31, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x22, 0x77, 0x69, 0x64, 0x67, 0x65, 0x74, 0x5F, 0x74, 0x79, 0x70, 0x65, 0x22, 0x3A, 0x20, 0x22,
|
||||
0x6C, 0x69, 0x73, 0x74, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22,
|
||||
0x77, 0x69, 0x64, 0x67, 0x65, 0x74, 0x5F, 0x6E, 0x61, 0x6D, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x50,
|
||||
0x6C, 0x65, 0x61, 0x73, 0x65, 0x20, 0x53, 0x65, 0x6C, 0x65, 0x63, 0x74, 0x20, 0x45, 0x72, 0x72,
|
||||
0x63, 0x6F, 0x64, 0x65, 0x22, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22,
|
||||
0x6C, 0x69, 0x73, 0x74, 0x5F, 0x69, 0x74, 0x65, 0x6D, 0x22, 0x3A, 0x20, 0x5B, 0x0A, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x69, 0x74, 0x65, 0x6D, 0x5F, 0x6E, 0x61, 0x6D, 0x65,
|
||||
0x22, 0x3A, 0x20, 0x22, 0x30, 0x78, 0x31, 0x45, 0x30, 0x32, 0x30, 0x30, 0x30, 0x30, 0x22, 0x0A,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x69, 0x74, 0x65, 0x6D, 0x5F, 0x6E, 0x61, 0x6D, 0x65, 0x22,
|
||||
0x3A, 0x20, 0x22, 0x30, 0x78, 0x31, 0x45, 0x30, 0x32, 0x30, 0x30, 0x30, 0x31, 0x22, 0x0A, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x22, 0x69, 0x74, 0x65, 0x6D, 0x5F, 0x6E, 0x61, 0x6D, 0x65, 0x22, 0x3A,
|
||||
0x20, 0x22, 0x30, 0x78, 0x31, 0x45, 0x30, 0x32, 0x30, 0x30, 0x30, 0x32, 0x22, 0x0A, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x22, 0x69, 0x74, 0x65, 0x6D, 0x5F, 0x6E, 0x61, 0x6D, 0x65, 0x22, 0x3A, 0x20,
|
||||
0x22, 0x30, 0x78, 0x31, 0x45, 0x30, 0x32, 0x30, 0x30, 0x30, 0x33, 0x22, 0x0A, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x22, 0x69, 0x74, 0x65, 0x6D, 0x5F, 0x6E, 0x61, 0x6D, 0x65, 0x22, 0x3A, 0x20, 0x22,
|
||||
0x30, 0x78, 0x31, 0x45, 0x30, 0x32, 0x30, 0x30, 0x30, 0x34, 0x22, 0x0A, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x5D, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69, 0x64, 0x67,
|
||||
0x65, 0x74, 0x5F, 0x69, 0x6E, 0x64, 0x65, 0x78, 0x22, 0x3A, 0x20, 0x31, 0x32, 0x2C, 0x0A, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69, 0x64, 0x67, 0x65, 0x74, 0x5F, 0x74,
|
||||
0x79, 0x70, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x6C, 0x69, 0x73, 0x74, 0x22, 0x2C, 0x0A, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69, 0x64, 0x67, 0x65, 0x74, 0x5F, 0x6E, 0x61,
|
||||
0x6D, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x50, 0x6C, 0x65, 0x61, 0x73, 0x65, 0x20, 0x53, 0x65, 0x6C,
|
||||
0x65, 0x63, 0x74, 0x20, 0x45, 0x72, 0x72, 0x4C, 0x65, 0x76, 0x65, 0x6C, 0x22, 0x2C, 0x0A, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x6C, 0x69, 0x73, 0x74, 0x5F, 0x69, 0x74, 0x65,
|
||||
0x6D, 0x22, 0x3A, 0x20, 0x5B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x69,
|
||||
0x74, 0x65, 0x6D, 0x5F, 0x6E, 0x61, 0x6D, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x45, 0x72, 0x72, 0x6F,
|
||||
0x72, 0x20, 0x6C, 0x65, 0x76, 0x65, 0x6C, 0x30, 0x22, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22,
|
||||
0x69, 0x74, 0x65, 0x6D, 0x5F, 0x6E, 0x61, 0x6D, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x45, 0x72, 0x72,
|
||||
0x6F, 0x72, 0x20, 0x6C, 0x65, 0x76, 0x65, 0x6C, 0x31, 0x22, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x22, 0x69, 0x74, 0x65, 0x6D, 0x5F, 0x6E, 0x61, 0x6D, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x45, 0x72,
|
||||
0x72, 0x6F, 0x72, 0x20, 0x6C, 0x65, 0x76, 0x65, 0x6C, 0x32, 0x22, 0x0A, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x22, 0x69, 0x74, 0x65, 0x6D, 0x5F, 0x6E, 0x61, 0x6D, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x45,
|
||||
0x72, 0x72, 0x6F, 0x72, 0x20, 0x6C, 0x65, 0x76, 0x65, 0x6C, 0x33, 0x22, 0x0A, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x22, 0x69, 0x74, 0x65, 0x6D, 0x5F, 0x6E, 0x61, 0x6D, 0x65, 0x22, 0x3A, 0x20, 0x22,
|
||||
0x45, 0x72, 0x72, 0x6F, 0x72, 0x20, 0x6C, 0x65, 0x76, 0x65, 0x6C, 0x34, 0x22, 0x0A, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x5D, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20,
|
||||
0x20, 0x20, 0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69,
|
||||
0x64, 0x67, 0x65, 0x74, 0x5F, 0x69, 0x6E, 0x64, 0x65, 0x78, 0x22, 0x3A, 0x20, 0x31, 0x33, 0x2C,
|
||||
0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69, 0x64, 0x67, 0x65, 0x74,
|
||||
0x5F, 0x74, 0x79, 0x70, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x62, 0x75, 0x74, 0x74, 0x6F, 0x6E, 0x22,
|
||||
0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69, 0x64, 0x67, 0x65,
|
||||
0x74, 0x5F, 0x6E, 0x61, 0x6D, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x49, 0x6E, 0x6A, 0x65, 0x63, 0x74,
|
||||
0x22, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x2C, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20,
|
||||
0x20, 0x7B, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69, 0x64, 0x67,
|
||||
0x65, 0x74, 0x5F, 0x69, 0x6E, 0x64, 0x65, 0x78, 0x22, 0x3A, 0x20, 0x31, 0x34, 0x2C, 0x0A, 0x20,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69, 0x64, 0x67, 0x65, 0x74, 0x5F, 0x74,
|
||||
0x79, 0x70, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x62, 0x75, 0x74, 0x74, 0x6F, 0x6E, 0x22, 0x2C, 0x0A,
|
||||
0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x22, 0x77, 0x69, 0x64, 0x67, 0x65, 0x74, 0x5F,
|
||||
0x6E, 0x61, 0x6D, 0x65, 0x22, 0x3A, 0x20, 0x22, 0x45, 0x6C, 0x69, 0x6D, 0x69, 0x6E, 0x61, 0x74,
|
||||
0x65, 0x22, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x7D, 0x0A, 0x20, 0x20, 0x20, 0x20, 0x5D,
|
||||
0x0A, 0x20, 0x20, 0x7D, 0x0A, 0x7D, 0x0A
|
||||
};
|
||||
|
||||
#endif /* __widget_config_json_h_included */
|
||||
|
||||
@ -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;
|
||||
|
||||
@ -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,29 @@ 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 +106,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;
|
||||
}
|
||||
|
||||
@ -124,7 +150,7 @@ T_DjiReturnCode Osal_UdpSendData(T_DjiSocketHandle socketHandle, const char *ipA
|
||||
addr.sin_port = htons(port);
|
||||
addr.sin_addr.s_addr = inet_addr(ipAddr);
|
||||
|
||||
ret = sendto(socketHandleStruct->socketFd, buf, len, MSG_DONTWAIT, (struct sockaddr *) &addr, sizeof(struct sockaddr_in));
|
||||
ret = sendto(socketHandleStruct->socketFd, buf, len, 0, (struct sockaddr *) &addr, sizeof(struct sockaddr_in));
|
||||
if (ret >= 0) {
|
||||
*realLen = ret;
|
||||
} else {
|
||||
|
||||
@ -64,6 +64,8 @@ extern "C" {
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_FC_SUBSCRIPTION_ON
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_HMS_ON
|
||||
|
||||
/*!< Attention: This function needs to be used together with mobile sdk mop sample.
|
||||
* */
|
||||
//#define CONFIG_MODULE_SAMPLE_MOP_CHANNEL_ON
|
||||
|
||||
@ -39,6 +39,7 @@
|
||||
#include <mop_channel/test_mop_channel.h>
|
||||
#include <payload_collaboration/test_payload_collaboration.h>
|
||||
#include <xport/test_payload_xport.h>
|
||||
#include <hms/test_hms.h>
|
||||
#include "monitor/sys_monitor.h"
|
||||
#include "osal/osal.h"
|
||||
#include "osal/osal_fs.h"
|
||||
@ -87,6 +88,7 @@ static T_DjiReturnCode DjiUser_LocalWriteFsInit(const char *path);
|
||||
static void *DjiUser_MonitorTask(void *argument);
|
||||
static T_DjiReturnCode DjiTest_HighPowerApplyPinInit();
|
||||
static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState);
|
||||
static void DjiUser_NormalExitHandler(int signalNum);
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
int main(int argc, char **argv)
|
||||
@ -94,10 +96,19 @@ int main(int argc, char **argv)
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiUserInfo userInfo;
|
||||
T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo;
|
||||
T_DjiFirmwareVersion firmwareVersion = {
|
||||
.majorVersion = 1,
|
||||
.minorVersion = 0,
|
||||
.modifyVersion = 0,
|
||||
.debugVersion = 0,
|
||||
};
|
||||
|
||||
USER_UTIL_UNUSED(argc);
|
||||
USER_UTIL_UNUSED(argv);
|
||||
|
||||
// attention: when the program is hand up ctrl-c will generate the coredump file
|
||||
signal(SIGTERM, DjiUser_NormalExitHandler);
|
||||
|
||||
/*!< Step 1: Prepare system environment, such as osal, hal uart, console function and so on. */
|
||||
returnCode = DjiUser_PrepareSystemEnvironment();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -131,6 +142,18 @@ int main(int argc, char **argv)
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
returnCode = DjiCore_SetFirmwareVersion(firmwareVersion);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("set firmware version error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
returnCode = DjiCore_SetSerialNumber("PSDK12345678XX");
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("set serial number error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
/*!< Step 4: Initialize the selected modules by macros in dji_sdk_config.h . */
|
||||
#ifdef CONFIG_MODULE_SAMPLE_POWER_MANAGEMENT_ON
|
||||
T_DjiTestApplyHighPowerHandler applyHighPowerHandler = {
|
||||
@ -228,12 +251,9 @@ int main(int argc, char **argv)
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_MOP_CHANNEL_ON
|
||||
if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 ||
|
||||
aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_XPORT) {
|
||||
returnCode = DjiTest_MopChannelStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("mop channel sample init error");
|
||||
}
|
||||
returnCode = DjiTest_MopChannelStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("mop channel sample init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -272,6 +292,13 @@ int main(int argc, char **argv)
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_HMS_ON
|
||||
returnCode = DjiTest_HmsStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("hms test init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
/*!< Step 5: Tell the DJI Pilot you are ready. */
|
||||
returnCode = DjiCore_ApplicationStart();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -660,6 +687,12 @@ static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinSta
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
static void DjiUser_NormalExitHandler(int signalNum)
|
||||
{
|
||||
USER_UTIL_UNUSED(signalNum);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
#pragma GCC diagnostic pop
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF 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
|
||||
|
||||
80
samples/sample_c/platform/linux/nvidia_jeston/CMakeLists.txt
Normal file
80
samples/sample_c/platform/linux/nvidia_jeston/CMakeLists.txt
Normal file
@ -0,0 +1,80 @@
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
project(dji_sdk_demo_on_jeston C)
|
||||
|
||||
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} -fprofile-arcs -ftest-coverage")
|
||||
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(../common)
|
||||
include_directories(../manifold2/application)
|
||||
|
||||
set(TOOLCHAIN_NAME aarch64-linux-gnu-gcc)
|
||||
add_definitions(-DPLATFORM_ARCH_aarch64=1)
|
||||
add_definitions(-DSYSTEM_ARCH_LINUX=1)
|
||||
|
||||
file(GLOB_RECURSE MODULE_COMMON_SRC ../common/*.c)
|
||||
file(GLOB_RECURSE MODULE_HAL_SRC hal/*.c)
|
||||
file(GLOB_RECURSE MODULE_APP_SRC application/*.c)
|
||||
message("-- Use payload sdk package")
|
||||
file(GLOB_RECURSE MODULE_SAMPLE_SRC
|
||||
../../../module_sample/*.c
|
||||
)
|
||||
|
||||
include_directories(../../../../../out/include)
|
||||
|
||||
add_library(${PACKAGE_NAME} STATIC IMPORTED GLOBAL)
|
||||
set_target_properties(${PACKAGE_NAME} PROPERTIES
|
||||
IMPORTED_LOCATION ${CMAKE_CURRENT_LIST_DIR}/../../../../../out/lib/${TOOLCHAIN_NAME}/lib${PACKAGE_NAME}.a
|
||||
)
|
||||
|
||||
if (NOT EXECUTABLE_OUTPUT_PATH)
|
||||
set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
|
||||
endif ()
|
||||
|
||||
add_executable(${PROJECT_NAME}
|
||||
${MODULE_APP_SRC}
|
||||
${MODULE_SAMPLE_SRC}
|
||||
${MODULE_COMMON_SRC}
|
||||
${MODULE_HAL_SRC})
|
||||
|
||||
target_link_libraries(${PROJECT_NAME} m)
|
||||
target_link_libraries(${PROJECT_NAME} ${PACKAGE_NAME})
|
||||
|
||||
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/../common/3rdparty)
|
||||
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_include_directories(${PROJECT_NAME} PRIVATE /usr/local/include/opus)
|
||||
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)
|
||||
|
||||
add_custom_command(TARGET ${PROJECT_NAME}
|
||||
PRE_LINK COMMAND cmake ..
|
||||
WORKING_DIRECTORY ${CMAKE_BINARY_DIR})
|
||||
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef DJI_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******/
|
||||
@ -0,0 +1,82 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef DJI_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
|
||||
|
||||
/*!< Attention: Select the sample you want to run here.
|
||||
* */
|
||||
#define CONFIG_MODULE_SAMPLE_POWER_MANAGEMENT_ON
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_CAMERA_EMU_ON
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_CAMERA_MEDIA_ON
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_XPORT_ON
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_WIDGET_ON
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_WIDGET_SPEAKER_ON
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_DATA_TRANSMISSION_ON
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_UPGRADE_ON
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_HMS_ON
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_FC_SUBSCRIPTION_ON
|
||||
|
||||
/*!< Attention: This function needs to be used together with mobile sdk mop sample.
|
||||
* */
|
||||
//#define CONFIG_MODULE_SAMPLE_MOP_CHANNEL_ON
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // DJI_SDK_CONFIG_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
698
samples/sample_c/platform/linux/nvidia_jeston/application/main.c
Normal file
698
samples/sample_c/platform/linux/nvidia_jeston/application/main.c
Normal file
@ -0,0 +1,698 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file main.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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <dji_platform.h>
|
||||
#include <dji_logger.h>
|
||||
#include <dji_core.h>
|
||||
#include <utils/util_misc.h>
|
||||
#include <errno.h>
|
||||
#include <signal.h>
|
||||
#include <power_management/test_power_management.h>
|
||||
#include <gimbal_emu/test_payload_gimbal_emu.h>
|
||||
#include <fc_subscription/test_fc_subscription.h>
|
||||
#include <camera_emu/test_payload_cam_emu_media.h>
|
||||
#include <camera_emu/test_payload_cam_emu_base.h>
|
||||
#include <upgrade/test_upgrade.h>
|
||||
#include <upgrade_platform_opt/upgrade_platform_opt_linux.h>
|
||||
#include <mop_channel/test_mop_channel.h>
|
||||
#include <payload_collaboration/test_payload_collaboration.h>
|
||||
#include <xport/test_payload_xport.h>
|
||||
#include <hms/test_hms.h>
|
||||
#include "monitor/sys_monitor.h"
|
||||
#include "osal/osal.h"
|
||||
#include "osal/osal_fs.h"
|
||||
#include "osal/osal_socket.h"
|
||||
#include "../hal/hal_uart.h"
|
||||
#include "../hal/hal_network.h"
|
||||
#include "../hal/hal_usb_bulk.h"
|
||||
#include "dji_sdk_app_info.h"
|
||||
#include "dji_aircraft_info.h"
|
||||
#include "widget/test_widget.h"
|
||||
#include "widget/test_widget_speaker.h"
|
||||
#include "widget_interaction_test/test_widget_interaction.h"
|
||||
#include "data_transmission/test_data_transmission.h"
|
||||
#include "dji_sdk_config.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_LOG_MAX_COUNT (10)
|
||||
#define DJI_SYSTEM_CMD_STR_MAX_SIZE (64)
|
||||
#define DJI_SYSTEM_RESULT_STR_MAX_SIZE (128)
|
||||
|
||||
#define DJI_USE_WIDGET_INTERACTION 0
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
typedef struct {
|
||||
pid_t tid;
|
||||
char name[16];
|
||||
float pcpu;
|
||||
} T_ThreadAttribute;
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
static FILE *s_djiLogFile;
|
||||
static FILE *s_djiLogFileCnt;
|
||||
static pthread_t s_monitorThread = 0;
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
static T_DjiReturnCode DjiUser_PrepareSystemEnvironment(void);
|
||||
static T_DjiReturnCode DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo);
|
||||
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_LocalWriteFsInit(const char *path);
|
||||
static void *DjiUser_MonitorTask(void *argument);
|
||||
static T_DjiReturnCode DjiTest_HighPowerApplyPinInit();
|
||||
static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState);
|
||||
static void DjiUser_NormalExitHandler(int signalNum);
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiUserInfo userInfo;
|
||||
T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo;
|
||||
T_DjiFirmwareVersion firmwareVersion = {
|
||||
.majorVersion = 1,
|
||||
.minorVersion = 0,
|
||||
.modifyVersion = 0,
|
||||
.debugVersion = 0,
|
||||
};
|
||||
|
||||
USER_UTIL_UNUSED(argc);
|
||||
USER_UTIL_UNUSED(argv);
|
||||
|
||||
// attention: when the program is hand up ctrl-c will generate the coredump file
|
||||
signal(SIGTERM, DjiUser_NormalExitHandler);
|
||||
|
||||
/*!< Step 1: Prepare system environment, such as osal, hal uart, console function and so on. */
|
||||
returnCode = DjiUser_PrepareSystemEnvironment();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Prepare system environment error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
/*!< Step 2: Fill your application information in dji_sdk_app_info.h and use this interface to fill it. */
|
||||
returnCode = DjiUser_FillInUserInfo(&userInfo);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Fill user info error, please check user info config");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
/*!< Step 3: Initialize the Payload SDK core by your application information. */
|
||||
returnCode = DjiCore_Init(&userInfo);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Core init error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
returnCode = DjiAircraftInfo_GetBaseInfo(&aircraftInfoBaseInfo);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("get aircraft base info error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
returnCode = DjiCore_SetAlias("PSDK_APPALIAS");
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("set alias error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
returnCode = DjiCore_SetFirmwareVersion(firmwareVersion);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("set firmware version error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
returnCode = DjiCore_SetSerialNumber("PSDK12345678XX");
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("set serial number error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
/*!< Step 4: Initialize the selected modules by macros in dji_sdk_config.h . */
|
||||
#ifdef CONFIG_MODULE_SAMPLE_POWER_MANAGEMENT_ON
|
||||
T_DjiTestApplyHighPowerHandler applyHighPowerHandler = {
|
||||
.pinInit = DjiTest_HighPowerApplyPinInit,
|
||||
.pinWrite = DjiTest_WriteHighPowerApplyPin,
|
||||
};
|
||||
|
||||
returnCode = DjiTest_RegApplyHighPowerHandler(&applyHighPowerHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("regsiter apply high power handler error");
|
||||
}
|
||||
|
||||
returnCode = DjiTest_PowerManagementStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("power management init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_DATA_TRANSMISSION_ON
|
||||
returnCode = DjiTest_DataTransmissionStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("widget sample init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
if (aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_EXTENSION_PORT &&
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK) {
|
||||
returnCode = DjiTest_WidgetInteractionStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("widget interaction sample init error");
|
||||
}
|
||||
|
||||
returnCode = DjiTest_WidgetSpeakerStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("widget speaker test init error");
|
||||
}
|
||||
} else {
|
||||
#ifdef CONFIG_MODULE_SAMPLE_CAMERA_EMU_ON
|
||||
returnCode = DjiTest_CameraEmuBaseStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("camera emu common init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_CAMERA_MEDIA_ON
|
||||
returnCode = DjiTest_CameraEmuMediaStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("camera emu media init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_FC_SUBSCRIPTION_ON
|
||||
returnCode = DjiTest_FcSubscriptionStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("data subscription sample init error\n");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON
|
||||
if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 ||
|
||||
aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) {
|
||||
if (DjiTest_GimbalStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("psdk gimbal init error");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_XPORT_ON
|
||||
if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_XPORT) {
|
||||
if (DjiTest_XPortStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("psdk xport init error");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_WIDGET_ON
|
||||
#if DJI_USE_WIDGET_INTERACTION
|
||||
returnCode = DjiTest_WidgetInteractionStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("widget interaction test init error");
|
||||
}
|
||||
#else
|
||||
returnCode = DjiTest_WidgetStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("widget sample init error");
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_WIDGET_SPEAKER_ON
|
||||
returnCode = DjiTest_WidgetSpeakerStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("widget speaker test init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_MOP_CHANNEL_ON
|
||||
returnCode = DjiTest_MopChannelStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("mop channel sample init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_PAYLOAD_COLLABORATION_ON
|
||||
if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 ||
|
||||
aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_XPORT) {
|
||||
returnCode = DjiTest_PayloadCollaborationStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Payload collaboration sample init error\n");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_UPGRADE_ON
|
||||
T_DjiTestUpgradePlatformOpt linuxUpgradePlatformOpt = {
|
||||
.rebootSystem = DjiUpgradePlatformLinux_RebootSystem,
|
||||
.cleanUpgradeProgramFileStoreArea = DjiUpgradePlatformLinux_CleanUpgradeProgramFileStoreArea,
|
||||
.createUpgradeProgramFile = DjiUpgradePlatformLinux_CreateUpgradeProgramFile,
|
||||
.writeUpgradeProgramFile = DjiUpgradePlatformLinux_WriteUpgradeProgramFile,
|
||||
.readUpgradeProgramFile = DjiUpgradePlatformLinux_ReadUpgradeProgramFile,
|
||||
.closeUpgradeProgramFile = DjiUpgradePlatformLinux_CloseUpgradeProgramFile,
|
||||
.replaceOldProgram = DjiUpgradePlatformLinux_ReplaceOldProgram,
|
||||
.setUpgradeRebootState = DjiUpgradePlatformLinux_SetUpgradeRebootState,
|
||||
.getUpgradeRebootState = DjiUpgradePlatformLinux_GetUpgradeRebootState,
|
||||
.cleanUpgradeRebootState = DjiUpgradePlatformLinux_CleanUpgradeRebootState,
|
||||
};
|
||||
T_DjiTestUpgradeConfig testUpgradeConfig = {
|
||||
.firmwareVersion = {1, 0, 0, 0},
|
||||
.transferType = DJI_FIRMWARE_TRANSFER_TYPE_DCFTP,
|
||||
.needReplaceProgramBeforeReboot = true
|
||||
};
|
||||
if (DjiTest_UpgradeStartService(&linuxUpgradePlatformOpt, testUpgradeConfig) !=
|
||||
DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("psdk upgrade init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_HMS_ON
|
||||
returnCode = DjiTest_HmsStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("hms test init error");
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/*!< Step 5: Tell the DJI Pilot you are ready. */
|
||||
returnCode = DjiCore_ApplicationStart();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("start sdk application error");
|
||||
}
|
||||
|
||||
if (pthread_create(&s_monitorThread, NULL, DjiUser_MonitorTask, NULL) != 0) {
|
||||
USER_LOG_ERROR("create monitor task fail.");
|
||||
}
|
||||
|
||||
if (pthread_setname_np(s_monitorThread, "monitor task") != 0) {
|
||||
USER_LOG_ERROR("set name for monitor task fail.");
|
||||
}
|
||||
|
||||
while (1) {
|
||||
sleep(1);
|
||||
}
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
static T_DjiReturnCode DjiUser_PrepareSystemEnvironment(void)
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiOsalHandler osalHandler = {
|
||||
.TaskCreate = Osal_TaskCreate,
|
||||
.TaskDestroy = Osal_TaskDestroy,
|
||||
.TaskSleepMs = Osal_TaskSleepMs,
|
||||
.MutexCreate= Osal_MutexCreate,
|
||||
.MutexDestroy = Osal_MutexDestroy,
|
||||
.MutexLock = Osal_MutexLock,
|
||||
.MutexUnlock = Osal_MutexUnlock,
|
||||
.SemaphoreCreate = Osal_SemaphoreCreate,
|
||||
.SemaphoreDestroy = Osal_SemaphoreDestroy,
|
||||
.SemaphoreWait = Osal_SemaphoreWait,
|
||||
.SemaphoreTimedWait = Osal_SemaphoreTimedWait,
|
||||
.SemaphorePost = Osal_SemaphorePost,
|
||||
.Malloc = Osal_Malloc,
|
||||
.Free = Osal_Free,
|
||||
.GetTimeMs = Osal_GetTimeMs,
|
||||
.GetTimeUs = Osal_GetTimeUs,
|
||||
};
|
||||
|
||||
T_DjiLoggerConsole printConsole = {
|
||||
.func = DjiUser_PrintConsole,
|
||||
.consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO,
|
||||
.isSupportColor = true,
|
||||
};
|
||||
|
||||
T_DjiLoggerConsole localRecordConsole = {
|
||||
.consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_DEBUG,
|
||||
.func = DjiUser_LocalWrite,
|
||||
.isSupportColor = true,
|
||||
};
|
||||
|
||||
T_DjiHalUartHandler uartHandler = {
|
||||
.UartInit = HalUart_Init,
|
||||
.UartDeInit = HalUart_DeInit,
|
||||
.UartWriteData = HalUart_WriteData,
|
||||
.UartReadData = HalUart_ReadData,
|
||||
.UartGetStatus = HalUart_GetStatus,
|
||||
};
|
||||
|
||||
T_DjiHalNetworkHandler networkHandler = {
|
||||
.NetworkInit = HalNetWork_Init,
|
||||
.NetworkDeInit = HalNetWork_DeInit,
|
||||
.NetworkGetDeviceInfo = HalNetWork_GetDeviceInfo,
|
||||
};
|
||||
|
||||
T_DjiHalUsbBulkHandler usbBulkHandler = {
|
||||
.UsbBulkInit = HalUsbBulk_Init,
|
||||
.UsbBulkDeInit = HalUsbBulk_DeInit,
|
||||
.UsbBulkWriteData = HalUsbBulk_WriteData,
|
||||
.UsbBulkReadData = HalUsbBulk_ReadData,
|
||||
.UsbBulkGetDeviceInfo = HalUsbBulk_GetDeviceInfo,
|
||||
};
|
||||
|
||||
T_DjiFileSystemHandler fileSystemHandler = {
|
||||
.FileOpen = Osal_FileOpen,
|
||||
.FileClose = Osal_FileClose,
|
||||
.FileWrite = Osal_FileWrite,
|
||||
.FileRead = Osal_FileRead,
|
||||
.FileSync = Osal_FileSync,
|
||||
.FileSeek = Osal_FileSeek,
|
||||
.DirOpen = Osal_DirOpen,
|
||||
.DirClose = Osal_DirClose,
|
||||
.DirRead = Osal_DirRead,
|
||||
.Mkdir = Osal_Mkdir,
|
||||
.Unlink = Osal_Unlink,
|
||||
.Rename = Osal_Rename,
|
||||
.Stat = Osal_Stat,
|
||||
};
|
||||
|
||||
T_DjiSocketHandler socketHandler = {
|
||||
.Socket = Osal_Socket,
|
||||
.Bind = Osal_Bind,
|
||||
.Close = Osal_Close,
|
||||
.UdpSendData = Osal_UdpSendData,
|
||||
.UdpRecvData = Osal_UdpRecvData,
|
||||
.TcpListen = Osal_TcpListen,
|
||||
.TcpAccept = Osal_TcpAccept,
|
||||
.TcpConnect = Osal_TcpConnect,
|
||||
.TcpSendData = Osal_TcpSendData,
|
||||
.TcpRecvData = Osal_TcpRecvData,
|
||||
};
|
||||
|
||||
returnCode = DjiPlatform_RegOsalHandler(&osalHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
printf("register osal handler error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
returnCode = DjiPlatform_RegHalUartHandler(&uartHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
printf("register hal uart handler error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
if (DjiUser_LocalWriteFsInit(DJI_LOG_PATH) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
printf("file system init error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
}
|
||||
|
||||
returnCode = DjiLogger_AddConsole(&printConsole);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
printf("add printf console error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
returnCode = DjiLogger_AddConsole(&localRecordConsole);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
printf("add printf console error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
#if (CONFIG_HARDWARE_CONNECTION == DJI_USE_UART_AND_USB_BULK_DEVICE)
|
||||
returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
printf("register hal usb bulk handler error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_UART_AND_NETWORK_DEVICE)
|
||||
returnCode = DjiPlatform_RegHalNetworkHandler(&networkHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
printf("register hal network handler error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
//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) {
|
||||
printf("register osal socket handler error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_UART)
|
||||
/*!< Attention: Only use uart hardware connection.
|
||||
*/
|
||||
#endif
|
||||
|
||||
returnCode = DjiPlatform_RegFileSystemHandler(&fileSystemHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
printf("register osal filesystem handler error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo)
|
||||
{
|
||||
if (userInfo == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
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.");
|
||||
sleep(1);
|
||||
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.");
|
||||
sleep(1);
|
||||
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;
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiUser_PrintConsole(const uint8_t *data, uint16_t dataLen)
|
||||
{
|
||||
USER_UTIL_UNUSED(dataLen);
|
||||
|
||||
printf("%s", data);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiUser_LocalWrite(const uint8_t *data, uint16_t dataLen)
|
||||
{
|
||||
uint32_t realLen;
|
||||
|
||||
if (s_djiLogFile == NULL) {
|
||||
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;
|
||||
}
|
||||
}
|
||||
|
||||
static T_DjiReturnCode 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(NULL);
|
||||
struct tm *localTime = localtime(¤tTime);
|
||||
uint16_t logFileIndex = 0;
|
||||
uint16_t currentLogFileIndex;
|
||||
uint8_t ret;
|
||||
|
||||
if (localTime == NULL) {
|
||||
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) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
}
|
||||
|
||||
s_djiLogFileCnt = fopen(DJI_LOG_INDEX_FILE_NAME, "rb+");
|
||||
if (s_djiLogFileCnt == NULL) {
|
||||
s_djiLogFileCnt = fopen(DJI_LOG_INDEX_FILE_NAME, "wb+");
|
||||
if (s_djiLogFileCnt == NULL) {
|
||||
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 == NULL) {
|
||||
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;
|
||||
}
|
||||
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wmissing-noreturn"
|
||||
#pragma GCC diagnostic ignored "-Wreturn-type"
|
||||
|
||||
static void *DjiUser_MonitorTask(void *argument)
|
||||
{
|
||||
unsigned int i = 0;
|
||||
unsigned int threadCount = 0;
|
||||
pid_t *tidList = NULL;
|
||||
T_ThreadAttribute *threadAttribute = NULL;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
|
||||
USER_UTIL_UNUSED(argument);
|
||||
|
||||
while (1) {
|
||||
threadCount = Monitor_GetThreadCountOfProcess(getpid());
|
||||
tidList = osalHandler->Malloc(threadCount * sizeof(pid_t));
|
||||
if (tidList == NULL) {
|
||||
USER_LOG_ERROR("malloc fail.");
|
||||
goto delay;
|
||||
}
|
||||
Monitor_GetTidListOfProcess(getpid(), tidList, threadCount);
|
||||
|
||||
threadAttribute = osalHandler->Malloc(threadCount * sizeof(T_ThreadAttribute));
|
||||
if (threadAttribute == NULL) {
|
||||
USER_LOG_ERROR("malloc fail.");
|
||||
goto freeTidList;
|
||||
}
|
||||
for (i = 0; i < threadCount; ++i) {
|
||||
threadAttribute[i].tid = tidList[i];
|
||||
}
|
||||
|
||||
USER_LOG_DEBUG("thread pcpu:");
|
||||
USER_LOG_DEBUG("tid\tname\tpcpu");
|
||||
for (i = 0; i < threadCount; ++i) {
|
||||
threadAttribute[i].pcpu = Monitor_GetPcpuOfThread(getpid(), tidList[i]);
|
||||
Monitor_GetNameOfThread(getpid(), tidList[i], threadAttribute[i].name, sizeof(threadAttribute[i].name));
|
||||
USER_LOG_DEBUG("%d\t%15s\t%f %%.", threadAttribute[i].tid, threadAttribute[i].name,
|
||||
threadAttribute[i].pcpu);
|
||||
}
|
||||
|
||||
USER_LOG_DEBUG("heap used: %d B.", Monitor_GetHeapUsed(getpid()));
|
||||
USER_LOG_DEBUG("stack used: %d B.", Monitor_GetStackUsed(getpid()));
|
||||
|
||||
osalHandler->Free(threadAttribute);
|
||||
freeTidList:
|
||||
osalHandler->Free(tidList);
|
||||
|
||||
delay:
|
||||
sleep(10);
|
||||
}
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
static void DjiUser_NormalExitHandler(int signalNum)
|
||||
{
|
||||
USER_UTIL_UNUSED(signalNum);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
#pragma GCC diagnostic pop
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
@ -0,0 +1,90 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file hal_network.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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* 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****/
|
||||
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef 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******/
|
||||
260
samples/sample_c/platform/linux/nvidia_jeston/hal/hal_uart.c
Normal file
260
samples/sample_c/platform/linux/nvidia_jeston/hal/hal_uart.c
Normal 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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* 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 {
|
||||
int32_t 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 = NULL;
|
||||
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****/
|
||||
65
samples/sample_c/platform/linux/nvidia_jeston/hal/hal_uart.h
Normal file
65
samples/sample_c/platform/linux/nvidia_jeston/hal/hal_uart.h
Normal 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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef 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******/
|
||||
224
samples/sample_c/platform/linux/nvidia_jeston/hal/hal_usb_bulk.c
Normal file
224
samples/sample_c/platform/linux/nvidia_jeston/hal/hal_usb_bulk.c
Normal 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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* 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****/
|
||||
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef 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******/
|
||||
@ -23,6 +23,8 @@
|
||||
*********************************************************************
|
||||
*/
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <widget/test_widget_speaker.h>
|
||||
#include <hms/test_hms.h>
|
||||
#include "FreeRTOS.h"
|
||||
#include "FreeRTOSConfig.h"
|
||||
#include "task.h"
|
||||
@ -101,7 +103,6 @@ void DjiUser_StartTask(void const *argument)
|
||||
.consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO,
|
||||
.isSupportColor = true,
|
||||
};
|
||||
|
||||
T_DjiHalUartHandler uartHandler = {
|
||||
.UartInit = HalUart_Init,
|
||||
.UartDeInit = HalUart_DeInit,
|
||||
@ -109,6 +110,12 @@ void DjiUser_StartTask(void const *argument)
|
||||
.UartReadData = HalUart_ReadData,
|
||||
.UartGetStatus = HalUart_GetStatus,
|
||||
};
|
||||
T_DjiFirmwareVersion firmwareVersion = {
|
||||
.majorVersion = 1,
|
||||
.minorVersion = 0,
|
||||
.modifyVersion = 0,
|
||||
.debugVersion = 0,
|
||||
};
|
||||
|
||||
UART_Init(DJI_CONSOLE_UART_NUM, DJI_CONSOLE_UART_BAUD);
|
||||
Led_Init(LED3);
|
||||
@ -161,6 +168,18 @@ void DjiUser_StartTask(void const *argument)
|
||||
goto out;
|
||||
}
|
||||
|
||||
returnCode = DjiCore_SetFirmwareVersion(firmwareVersion);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("set firmware version error");
|
||||
goto out;
|
||||
}
|
||||
|
||||
returnCode = DjiCore_SetSerialNumber("PSDK12345678XX");
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("set serial number error");
|
||||
goto out;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_POWER_MANAGEMENT_ON
|
||||
T_DjiTestApplyHighPowerHandler applyHighPowerHandler = {
|
||||
.pinInit = DjiTest_HighPowerApplyPinInit,
|
||||
@ -185,6 +204,13 @@ void DjiUser_StartTask(void const *argument)
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_WIDGET_SPEAKER_ON
|
||||
returnCode = DjiTest_WidgetSpeakerStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("widget speaker sample init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_DATA_TRANSMISSION_ON
|
||||
returnCode = DjiTest_DataTransmissionStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -199,20 +225,37 @@ void DjiUser_StartTask(void const *argument)
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_HMS_ON
|
||||
returnCode = DjiTest_HmsStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("hms test init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
#if !USE_USB_HOST_UART
|
||||
#ifdef CONFIG_MODULE_SAMPLE_CAMERA_ON
|
||||
returnCode = DjiTest_CameraEmuBaseStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("camera emu common init error");
|
||||
goto out;
|
||||
if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK
|
||||
&& aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) {
|
||||
USER_LOG_WARN("Not support camera emu sample.");
|
||||
} else {
|
||||
returnCode = DjiTest_CameraEmuBaseStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("camera emu common init error");
|
||||
goto out;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON
|
||||
if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 ||
|
||||
aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) {
|
||||
if (DjiTest_GimbalStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("psdk gimbal init error");
|
||||
if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK
|
||||
&& aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) {
|
||||
USER_LOG_WARN("Not support gimbal emu sample.");
|
||||
} else {
|
||||
if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 ||
|
||||
aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) {
|
||||
if (DjiTest_GimbalStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("psdk gimbal init error");
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -38,6 +38,8 @@ extern "C" {
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_WIDGET_ON
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_WIDGET_SPEAKER_ON
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_DATA_TRANSMISSION_ON
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_FC_SUBSCRIPTION_ON
|
||||
@ -50,6 +52,8 @@ extern "C" {
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_UPGRADE_ON
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_HMS_ON
|
||||
|
||||
/*!< Attention: Please uncomment it in gps environment.
|
||||
* */
|
||||
//#define CONFIG_MODULE_SAMPLE_TIME_SYNC_ON
|
||||
|
||||
@ -30,7 +30,9 @@
|
||||
#include "dji_platform.h"
|
||||
|
||||
#if USE_USB_HOST_UART
|
||||
|
||||
#include "usbh_cdc.h"
|
||||
|
||||
#endif
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
@ -53,7 +55,7 @@ T_DjiReturnCode HalUart_Init(E_DjiHalUartNum uartNum, uint32_t baudRate, T_DjiUa
|
||||
{
|
||||
T_UartHandleStruct *uartHandleStruct;
|
||||
|
||||
uartHandleStruct = malloc(sizeof(T_UartHandleStruct));
|
||||
uartHandleStruct = pvPortMalloc(sizeof(T_UartHandleStruct));
|
||||
if (uartHandleStruct == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_MEMORY_ALLOC_FAILED;
|
||||
}
|
||||
@ -72,12 +74,15 @@ T_DjiReturnCode HalUart_Init(E_DjiHalUartNum uartNum, uint32_t baudRate, T_DjiUa
|
||||
|
||||
T_DjiReturnCode HalUart_DeInit(T_DjiUartHandle uartHandle)
|
||||
{
|
||||
vPortFree(uartHandle);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf, uint32_t len, uint32_t *realLen)
|
||||
{
|
||||
T_UartHandleStruct *uartHandleStruct = (T_UartHandleStruct *) uartHandle;
|
||||
int32_t ret;
|
||||
|
||||
if (uartHandleStruct->uartNum == USER_UART_NUM0) {
|
||||
UART_Write(COMMUNICATION_UART_NUM, buf, len);
|
||||
@ -91,6 +96,7 @@ T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf
|
||||
T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen)
|
||||
{
|
||||
T_UartHandleStruct *uartHandleStruct = (T_UartHandleStruct *) uartHandle;
|
||||
int32_t ret;
|
||||
|
||||
if (uartHandleStruct->uartNum == USER_UART_NUM0) {
|
||||
*realLen = UART_Read(COMMUNICATION_UART_NUM, buf, len);
|
||||
|
||||
@ -1,150 +0,0 @@
|
||||
#THIS FILE IS AUTO GENERATED FROM THE TEMPLATE! DO NOT CHANGE!
|
||||
set(CMAKE_SYSTEM_NAME Generic)
|
||||
set(CMAKE_SYSTEM_VERSION 1)
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
|
||||
# project settings
|
||||
project(dji_sdk_demo_rtos C CXX ASM)
|
||||
set(CMAKE_CXX_STANDARD 17)
|
||||
set(CMAKE_C_STANDARD 11)
|
||||
|
||||
set(DEVICE STM32F407IG)
|
||||
set(DEVICE_FAMILY STM32F40_41xxx)
|
||||
set(USE_BOOTLOADER NO)
|
||||
|
||||
if (USE_BOOTLOADER MATCHES YES)
|
||||
add_definitions(-DUSE_BOOTLOADER)
|
||||
endif ()
|
||||
add_definitions(-DUSE_HAL_DRIVER)
|
||||
add_definitions(-DSTM32F407xx)
|
||||
add_definitions(-DUSE_CMSIS_RTOS=1)
|
||||
add_definitions(-DHSE_VALUE=8000000)
|
||||
#add_definitions(-DUSE_USB_HOST_UART=1)
|
||||
|
||||
#Uncomment for hardware floating point
|
||||
add_compile_definitions(ARM_MATH_CM4;ARM_MATH_MATRIX_CHECK;ARM_MATH_ROUNDING)
|
||||
add_compile_options(-mfloat-abi=hard -mfpu=fpv4-sp-d16)
|
||||
add_link_options(-mfloat-abi=hard -mfpu=fpv4-sp-d16)
|
||||
|
||||
#Uncomment for software floating point
|
||||
#add_compile_options(-mfloat-abi=soft)
|
||||
|
||||
add_compile_options(-mcpu=cortex-m4 -mthumb -mthumb-interwork)
|
||||
add_compile_options(-ffunction-sections -fdata-sections -fno-common -fmessage-length=0)
|
||||
|
||||
# uncomment to mitigate c++17 absolute addresses warnings
|
||||
#set(ADDITIONAL_CORE_FLAGS "-Wno-unused-function -Wno-missing-braces")
|
||||
#set(CORE_FLAGS "-mthumb -mcpu=cortex-m4 -mlittle-endian -mfpu=fpv4-sp-d16 -mfloat-abi=softfp -mthumb-interwork --specs=nano.specs --specs=nosys.specs ${ADDITIONAL_CORE_FLAGS}")
|
||||
set(CMAKE_C_FLAGS "${CORE_FLAGS} -fno-builtin -Wall -std=gnu99 -fdata-sections -ffunction-sections -u _printf_float --specs=nosys.specs -g3 -gdwarf-2" CACHE INTERNAL "c compiler flags")
|
||||
#set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-register")
|
||||
|
||||
if ("${CMAKE_BUILD_TYPE}" STREQUAL "Release")
|
||||
message(STATUS "Maximum optimization for speed")
|
||||
add_compile_options(-Ofast)
|
||||
elseif ("${CMAKE_BUILD_TYPE}" STREQUAL "RelWithDebInfo")
|
||||
message(STATUS "Maximum optimization for speed, debug info included")
|
||||
add_compile_options(-Ofast -g)
|
||||
elseif ("${CMAKE_BUILD_TYPE}" STREQUAL "MinSizeRel")
|
||||
message(STATUS "Maximum optimization for size")
|
||||
add_compile_options(-Os)
|
||||
else ()
|
||||
message(STATUS "Minimal optimization, debug info included")
|
||||
# add_compile_options(-Og -g)
|
||||
endif ()
|
||||
|
||||
include_directories(
|
||||
../../../common/osal
|
||||
../../hal
|
||||
../../application
|
||||
../../bootloader
|
||||
../../drivers/BSP
|
||||
../../drivers/STM32F4xx_HAL_Driver/Inc
|
||||
../../drivers/STM32F4xx_HAL_Driver/Inc/Legacy
|
||||
../../drivers/CMSIS/Device/ST/STM32F4xx/Include
|
||||
../../drivers/CMSIS/Include
|
||||
../../middlewares/Third_Party/FreeRTOS/Source/include
|
||||
../../middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS
|
||||
../../middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F
|
||||
../../../../../module_sample
|
||||
../../drivers/USB_HOST/Target
|
||||
../../drivers/USB_HOST/App
|
||||
../../middlewares/ST/STM32_USB_Host_Library/Core/Inc
|
||||
../../middlewares/ST/STM32_USB_Host_Library/Class/CDC/Inc
|
||||
)
|
||||
|
||||
add_definitions(-DUSE_HAL_DRIVER -DSTM32F407xx)
|
||||
|
||||
file(GLOB_RECURSE SOURCES
|
||||
"../../../common/*.c"
|
||||
"../../hal/*.c"
|
||||
"../../application/*.c"
|
||||
"../../drivers/BSP/*.c"
|
||||
"../../drivers/USB_HOST/*.*"
|
||||
"../../middlewares/ST/*.*"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/*.*"
|
||||
"../../drivers/CMSIS/Device/ST/STM32F4xx/Source/Templates/system_stm32f4xx.c"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS/cmsis_os.c"
|
||||
"../../drivers/CMSIS/Device/ST/STM32F4xx/Source/Templates/gcc/startup_stm32f407xx.s"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/portable/MemMang/heap_4.c"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/croutine.c"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/event_groups.c"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/list.c"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/queue.c"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/tasks.c"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/timers.c"
|
||||
|
||||
"../../../../../module_sample/camera_emu/test_payload_cam_emu_base.c"
|
||||
"../../../../../module_sample/gimbal_emu/*.c"
|
||||
"../../../../../module_sample/xport/*.c"
|
||||
"../../../../../module_sample/payload_collaboration/*.c"
|
||||
"../../../../../module_sample/fc_subscription/*.c"
|
||||
"../../../../../module_sample/data_transmission/*.c"
|
||||
"../../../../../module_sample/widget/*.c"
|
||||
"../../../../../module_sample/positioning/*.c"
|
||||
"../../../../../module_sample/time_sync/*.c"
|
||||
"../../../../../module_sample/upgrade/*.c"
|
||||
"../../../../../module_sample/utils/*.c"
|
||||
"../../../../../module_sample/power_management/*.c"
|
||||
)
|
||||
|
||||
if (USE_BOOTLOADER MATCHES YES)
|
||||
set(FLASH_START 0x08010000)
|
||||
set(FLASH_SIZE 448k)
|
||||
else ()
|
||||
set(FLASH_START 0x08000000)
|
||||
set(FLASH_SIZE 1024k)
|
||||
endif ()
|
||||
|
||||
set(RAM_SIZE 128k)
|
||||
set(CCMRAM_SIZE 64k)
|
||||
set(HEAP_SIZE 0x800)
|
||||
set(STACK_SIZE 0x800)
|
||||
|
||||
configure_file(linker_script/stm32f407igt.ld.in ${CMAKE_CURRENT_BINARY_DIR}/stm32f407igt.ld)
|
||||
get_filename_component(LINKER_SCRIPT ${CMAKE_CURRENT_BINARY_DIR}/stm32f407igt.ld ABSOLUTE)
|
||||
|
||||
add_link_options(-Wl,-gc-sections,--print-memory-usage,-Map=${PROJECT_BINARY_DIR}/${PROJECT_NAME}.map)
|
||||
add_link_options(-mcpu=cortex-m4 -mthumb -mthumb-interwork)
|
||||
add_link_options(-T ${LINKER_SCRIPT})
|
||||
|
||||
include_directories(../../../../../../../out/include)
|
||||
link_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../../../out/lib/arm-none-eabi-gcc)
|
||||
link_libraries(${CMAKE_CURRENT_LIST_DIR}/../../../../../../../out/lib/arm-none-eabi-gcc/libpayloadsdk.a)
|
||||
|
||||
add_executable(${PROJECT_NAME}.elf ${SOURCES} ${LINKER_SCRIPT})
|
||||
|
||||
set(HEX_FILE ${PROJECT_BINARY_DIR}/${PROJECT_NAME}.hex)
|
||||
set(BIN_FILE ${PROJECT_BINARY_DIR}/${PROJECT_NAME}.bin)
|
||||
|
||||
add_custom_command(TARGET ${PROJECT_NAME}.elf POST_BUILD
|
||||
COMMAND ${CMAKE_OBJCOPY} -Oihex $<TARGET_FILE:${PROJECT_NAME}.elf> ${HEX_FILE}
|
||||
COMMAND ${CMAKE_OBJCOPY} -Obinary $<TARGET_FILE:${PROJECT_NAME}.elf> ${BIN_FILE}
|
||||
COMMENT "Building ${HEX_FILE}
|
||||
Building ${BIN_FILE}")
|
||||
|
||||
configure_file(${CMAKE_CURRENT_LIST_DIR}/download_script/download.jlink.in ${CMAKE_CURRENT_BINARY_DIR}/download.jlink)
|
||||
configure_file(${CMAKE_CURRENT_LIST_DIR}/download_script/download.sh.in ${CMAKE_CURRENT_BINARY_DIR}/download.sh)
|
||||
configure_file(${CMAKE_CURRENT_LIST_DIR}/debug_script/gdbserver.sh.in ${CMAKE_CURRENT_BINARY_DIR}/gdbserver.sh)
|
||||
execute_process(COMMAND chmod 777 download.sh WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
|
||||
execute_process(COMMAND chmod 777 gdbserver.sh WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
|
||||
@ -1,2 +0,0 @@
|
||||
#!/bin/bash
|
||||
JLinkGDBServerCLExe -device ${DEVICE} -speed 8100 -if SWD -s -halt -noir -x ${CMAKE_CURRENT_LIST_DIR}/debug_script/init.gdb -rtos GDBServer/RTOSPlugin_FreeRTOS
|
||||
@ -1 +0,0 @@
|
||||
reset
|
||||
@ -1,7 +0,0 @@
|
||||
device ${DEVICE}
|
||||
r
|
||||
loadbin ${PROJECT_NAME}.bin, ${FLASH_START}
|
||||
verifybin ${PROJECT_NAME}.bin, ${FLASH_START}
|
||||
r
|
||||
g
|
||||
qc
|
||||
@ -1,9 +0,0 @@
|
||||
#!/bin/bash
|
||||
if [ ! -n "$1" ] ;then
|
||||
JLinkExe -device ${DEVICE} -speed 1000 -if SWD -CommanderScript ${CMAKE_CURRENT_BINARY_DIR}/download.jlink
|
||||
echo "use default jlink device"
|
||||
else
|
||||
JLinkExe -usb $1 -device ${DEVICE} -speed 1000 -if SWD -CommanderScript ${CMAKE_CURRENT_BINARY_DIR}/download.jlink
|
||||
echo "use selected jlink device, sn:"$1
|
||||
fi
|
||||
exit 0
|
||||
@ -1,190 +0,0 @@
|
||||
/* Default STM32F4xx linker script.
|
||||
*
|
||||
* Modify memory sections according to the targeted platform.
|
||||
*/
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = ${FLASH_START}, LENGTH = ${FLASH_SIZE}
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = ${RAM_SIZE}
|
||||
CCMRAM (rw) : ORIGIN = 0x10000000, LENGTH = ${CCMRAM_SIZE}
|
||||
}
|
||||
|
||||
/* Reset_Handler : Entry of reset handler */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/* Linker script to place sections and symbol values. Should be used together
|
||||
* with other linker script that defines memory regions FLASH and RAM.
|
||||
* It defines following symbols, which code can use without definition.
|
||||
* __exidx_start
|
||||
* __exidx_end
|
||||
* __etext
|
||||
* _sdata
|
||||
* __preinit_array_start
|
||||
* __preinit_array_end
|
||||
* __init_array_start
|
||||
* __init_array_end
|
||||
* __fini_array_start
|
||||
* __fini_array_end
|
||||
* _edata
|
||||
* _sbss
|
||||
* __bss_start__
|
||||
* __bss_end__
|
||||
* _ebss
|
||||
* __end__
|
||||
* end
|
||||
* __HeapLimit
|
||||
* __StackLimit
|
||||
* __StackTop
|
||||
* _sidata
|
||||
* _siccmram
|
||||
*/
|
||||
|
||||
_estack = ORIGIN(RAM) + LENGTH(RAM);
|
||||
_Min_Heap_Size = ${HEAP_SIZE};
|
||||
_Min_Stack_Size = ${STACK_SIZE};
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.text :
|
||||
{
|
||||
KEEP(*(.isr_vector))
|
||||
*(.text*)
|
||||
|
||||
KEEP(*(.init))
|
||||
KEEP(*(.fini))
|
||||
|
||||
/* .ctors */
|
||||
*crtbegin.o(.ctors)
|
||||
*crtbegin?.o(.ctors)
|
||||
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
|
||||
*(SORT(.ctors.*))
|
||||
*(.ctors)
|
||||
|
||||
/* .dtors */
|
||||
*crtbegin.o(.dtors)
|
||||
*crtbegin?.o(.dtors)
|
||||
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
|
||||
*(SORT(.dtors.*))
|
||||
*(.dtors)
|
||||
|
||||
*(.rodata*)
|
||||
|
||||
KEEP(*(.eh_frame*))
|
||||
} > FLASH
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
} > FLASH
|
||||
|
||||
__exidx_start = .;
|
||||
.ARM.exidx :
|
||||
{
|
||||
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
|
||||
} > FLASH
|
||||
__exidx_end = .;
|
||||
|
||||
__etext = .;
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = LOADADDR(.data);
|
||||
|
||||
.data : AT (__etext)
|
||||
{
|
||||
_sdata = .;
|
||||
*(vtable)
|
||||
*(.data*)
|
||||
|
||||
. = ALIGN(4);
|
||||
/* preinit data */
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP(*(.preinit_array))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
|
||||
. = ALIGN(4);
|
||||
/* init data */
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP(*(SORT(.init_array.*)))
|
||||
KEEP(*(.init_array))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
|
||||
|
||||
. = ALIGN(4);
|
||||
/* finit data */
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP(*(SORT(.fini_array.*)))
|
||||
KEEP(*(.fini_array))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
|
||||
KEEP(*(.jcr*))
|
||||
. = ALIGN(4);
|
||||
/* All data end */
|
||||
_edata = .;
|
||||
|
||||
} > RAM
|
||||
|
||||
_siccmram = LOADADDR(.ccmram);
|
||||
|
||||
/* CCM-RAM section
|
||||
*
|
||||
* IMPORTANT NOTE!
|
||||
* If initialized variables will be placed in this section,
|
||||
* the startup code needs to be modified to copy the init-values.
|
||||
*/
|
||||
.ccmram :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sccmram = .; /* create a global symbol at ccmram start */
|
||||
*(.ccmram)
|
||||
*(.ccmram*)
|
||||
|
||||
. = ALIGN(4);
|
||||
_eccmram = .; /* create a global symbol at ccmram end */
|
||||
} >CCMRAM AT> FLASH
|
||||
|
||||
.bss :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sbss = .;
|
||||
__bss_start__ = _sbss;
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = .;
|
||||
__bss_end__ = _ebss;
|
||||
} > RAM
|
||||
|
||||
.heap (COPY):
|
||||
{
|
||||
__end__ = .;
|
||||
PROVIDE(end = .);
|
||||
PROVIDE( _end = . );
|
||||
*(.heap*)
|
||||
__HeapLimit = .;
|
||||
} > RAM
|
||||
|
||||
/* .stack_dummy section doesn't contains any symbols. It is only
|
||||
* used for linker to calculate size of stack sections, and assign
|
||||
* values to stack symbols later */
|
||||
.stack_dummy (COPY):
|
||||
{
|
||||
*(.stack*)
|
||||
} > RAM
|
||||
|
||||
/* Set stack top to end of RAM, and stack limit move down by
|
||||
* size of stack_dummy section */
|
||||
__StackTop = ORIGIN(RAM) + LENGTH(RAM);
|
||||
__StackLimit = __StackTop - SIZEOF(.stack_dummy);
|
||||
PROVIDE(_estack = __StackTop);
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
/* Check if data + heap + stack exceeds RAM limit */
|
||||
ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed with stack")
|
||||
}
|
||||
@ -1,134 +0,0 @@
|
||||
#THIS FILE IS AUTO GENERATED FROM THE TEMPLATE! DO NOT CHANGE!
|
||||
set(CMAKE_SYSTEM_NAME Generic)
|
||||
set(CMAKE_SYSTEM_VERSION 1)
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
|
||||
# project settings
|
||||
project(dji_sdk_demo_bootloader C CXX ASM)
|
||||
set(CMAKE_CXX_STANDARD 17)
|
||||
set(CMAKE_C_STANDARD 11)
|
||||
|
||||
add_definitions(-DUSE_HAL_DRIVER)
|
||||
add_definitions(-DSTM32F407xx)
|
||||
add_definitions(-DUSE_CMSIS_RTOS=1)
|
||||
add_definitions(-DHSE_VALUE=8000000)
|
||||
set(DEVICE STM32F407IG)
|
||||
set(DEVICE_FAMILY STM32F40_41xxx)
|
||||
|
||||
#Uncomment for hardware floating point
|
||||
add_compile_definitions(ARM_MATH_CM4;ARM_MATH_MATRIX_CHECK;ARM_MATH_ROUNDING)
|
||||
add_compile_options(-mfloat-abi=hard -mfpu=fpv4-sp-d16)
|
||||
add_link_options(-mfloat-abi=hard -mfpu=fpv4-sp-d16)
|
||||
|
||||
#Uncomment for software floating point
|
||||
#add_compile_options(-mfloat-abi=soft)
|
||||
|
||||
add_compile_options(-mcpu=cortex-m4 -mthumb -mthumb-interwork)
|
||||
add_compile_options(-ffunction-sections -fdata-sections -fno-common -fmessage-length=0)
|
||||
|
||||
# uncomment to mitigate c++17 absolute addresses warnings
|
||||
#set(ADDITIONAL_CORE_FLAGS "-Wno-unused-function -Wno-missing-braces")
|
||||
#set(CORE_FLAGS "-mthumb -mcpu=cortex-m4 -mlittle-endian -mfpu=fpv4-sp-d16 -mfloat-abi=softfp -mthumb-interwork --specs=nano.specs --specs=nosys.specs ${ADDITIONAL_CORE_FLAGS}")
|
||||
set(CMAKE_C_FLAGS "${CORE_FLAGS} -fno-builtin -Wall -std=gnu99 -fdata-sections -ffunction-sections -g3 -gdwarf-2" CACHE INTERNAL "c compiler flags")
|
||||
#set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-register")
|
||||
|
||||
if ("${CMAKE_BUILD_TYPE}" STREQUAL "Release")
|
||||
message(STATUS "Maximum optimization for speed")
|
||||
add_compile_options(-Ofast)
|
||||
elseif ("${CMAKE_BUILD_TYPE}" STREQUAL "RelWithDebInfo")
|
||||
message(STATUS "Maximum optimization for speed, debug info included")
|
||||
add_compile_options(-Ofast -g)
|
||||
elseif ("${CMAKE_BUILD_TYPE}" STREQUAL "MinSizeRel")
|
||||
message(STATUS "Maximum optimization for size")
|
||||
add_compile_options(-Os)
|
||||
else ()
|
||||
message(STATUS "Minimal optimization, debug info included")
|
||||
add_compile_options(-Og -g)
|
||||
endif ()
|
||||
|
||||
include_directories(
|
||||
../../../common
|
||||
../../../common/osal
|
||||
../../hal
|
||||
../../application
|
||||
../../bootloader
|
||||
../../drivers/BSP
|
||||
../../drivers/STM32F4xx_HAL_Driver/Inc
|
||||
../../drivers/STM32F4xx_HAL_Driver/Inc/Legacy
|
||||
../../drivers/CMSIS/Device/ST/STM32F4xx/Include
|
||||
../../drivers/CMSIS/Include
|
||||
../../middlewares/Third_Party/FreeRTOS/Source/include
|
||||
../../middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F
|
||||
)
|
||||
|
||||
add_definitions(-DUSE_HAL_DRIVER -DSTM32F407xx)
|
||||
|
||||
file(GLOB_RECURSE SOURCES
|
||||
"../../../common/*.c"
|
||||
"../../hal/*.c"
|
||||
"../../bootloader/*.c"
|
||||
"../../drivers/BSP/*.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rng.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_can.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c"
|
||||
"../../drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c"
|
||||
"../../drivers/CMSIS/Device/ST/STM32F4xx/Source/Templates/system_stm32f4xx.c"
|
||||
"../../drivers/CMSIS/Device/ST/STM32F4xx/Source/Templates/gcc/startup_stm32f407xx.s"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/portable/MemMang/heap_4.c"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/croutine.c"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/event_groups.c"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/list.c"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/queue.c"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/tasks.c"
|
||||
"../../middlewares/Third_Party/FreeRTOS/Source/timers.c"
|
||||
)
|
||||
|
||||
#[[ LINK SCRIPT ]]
|
||||
set(FLASH_START 0x08000000)
|
||||
set(FLASH_SIZE 1024k)
|
||||
set(RAM_SIZE 128k)
|
||||
set(CCMRAM_SIZE 64k)
|
||||
set(HEAP_SIZE 0x800)
|
||||
set(STACK_SIZE 0x800)
|
||||
|
||||
include_directories(../../../../../../../out/include)
|
||||
|
||||
configure_file(linker_script/stm32f407igt.ld.in ${CMAKE_CURRENT_BINARY_DIR}/stm32f407igt.ld)
|
||||
get_filename_component(LINKER_SCRIPT ${CMAKE_CURRENT_BINARY_DIR}/stm32f407igt.ld ABSOLUTE)
|
||||
|
||||
add_link_options(-Wl,-gc-sections,--print-memory-usage,-Map=${PROJECT_BINARY_DIR}/${PROJECT_NAME}.map)
|
||||
add_link_options(-mcpu=cortex-m4 -mthumb -mthumb-interwork)
|
||||
add_link_options(-T ${LINKER_SCRIPT})
|
||||
|
||||
add_executable(${PROJECT_NAME}.elf ${SOURCES} ${LINKER_SCRIPT})
|
||||
|
||||
set(HEX_FILE ${PROJECT_BINARY_DIR}/${PROJECT_NAME}.hex)
|
||||
set(BIN_FILE ${PROJECT_BINARY_DIR}/${PROJECT_NAME}.bin)
|
||||
|
||||
add_custom_command(TARGET ${PROJECT_NAME}.elf POST_BUILD
|
||||
COMMAND ${CMAKE_OBJCOPY} -Oihex $<TARGET_FILE:${PROJECT_NAME}.elf> ${HEX_FILE}
|
||||
COMMAND ${CMAKE_OBJCOPY} -Obinary $<TARGET_FILE:${PROJECT_NAME}.elf> ${BIN_FILE}
|
||||
COMMENT "Building ${HEX_FILE}
|
||||
Building ${BIN_FILE}")
|
||||
|
||||
configure_file(${CMAKE_CURRENT_LIST_DIR}/download_script/download.jlink.in ${CMAKE_CURRENT_BINARY_DIR}/download.jlink)
|
||||
configure_file(${CMAKE_CURRENT_LIST_DIR}/download_script/download.sh.in ${CMAKE_CURRENT_BINARY_DIR}/download.sh)
|
||||
configure_file(${CMAKE_CURRENT_LIST_DIR}/debug_script/gdbserver.sh.in ${CMAKE_CURRENT_BINARY_DIR}/gdbserver.sh)
|
||||
execute_process(COMMAND chmod 777 download.sh WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
|
||||
execute_process(COMMAND chmod 777 gdbserver.sh WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
|
||||
@ -1,15 +0,0 @@
|
||||
Config items of CLion project:
|
||||
1. Go to https://segger.com/downloads/jlink/#J-LinkSoftwareAndDocumentationPack
|
||||
For x64 ubuntu:
|
||||
Download <J-Link Software and Documentation pack for Linux, DEB installer, 64-bit>, double click the downloaded file to install.
|
||||
2. Go to https://developer.arm.com/tools-and-software/open-source-software/developer-tools/gnu-toolchain/gnu-rm/downloads
|
||||
Download toolchain, for x64 ubuntu is <gcc-arm-none-eabi-9-2020-q2-update-x86_64-linux.tar.bz2>
|
||||
cd /usr/local/
|
||||
sudo tar xjf ~/Downloads/gcc-arm-none-eabi-9-2020-q2-update-x86_64-linux.tar.bz2
|
||||
add "export PATH=$PATH:/usr/local/gcc-arm-none-eabi-9-2020-q2-update/bin" to /etc/profile
|
||||
reboot system
|
||||
3. Create External Tool named "fw_download", Program is $CMakeCurrentBuildDir$/download.sh and Work Directory is $CMakeCurrentBuildDir$
|
||||
You can add shortcuts to this external tool to quickly download and run program.
|
||||
4. Create Embedded GDB Server, setting GDB Server to <cmake build dir>/gdbserver.sh, 'target remote' args to 127.0.0.1:2331
|
||||
|
||||
Note: double-check the all above path, and ensure they are correct
|
||||
@ -1,2 +0,0 @@
|
||||
#!/bin/bash
|
||||
JLinkGDBServerCLExe -device ${DEVICE} -speed 8100 -if SWD -s -halt -noir -x ${CMAKE_CURRENT_LIST_DIR}/debug_script/init.gdb -rtos GDBServer/RTOSPlugin_FreeRTOS
|
||||
@ -1 +0,0 @@
|
||||
reset
|
||||
@ -1,7 +0,0 @@
|
||||
device ${DEVICE}
|
||||
r
|
||||
loadbin ${PROJECT_NAME}.bin, ${FLASH_START}
|
||||
verifybin ${PROJECT_NAME}.bin, ${FLASH_START}
|
||||
r
|
||||
g
|
||||
qc
|
||||
@ -1,9 +0,0 @@
|
||||
#!/bin/bash
|
||||
if [ ! -n "$1" ] ;then
|
||||
JLinkExe -device ${DEVICE} -speed 1000 -if SWD -CommanderScript ${CMAKE_CURRENT_BINARY_DIR}/download.jlink
|
||||
echo "use default jlink device"
|
||||
else
|
||||
JLinkExe -usb $1 -device ${DEVICE} -speed 1000 -if SWD -CommanderScript ${CMAKE_CURRENT_BINARY_DIR}/download.jlink
|
||||
echo "use selected jlink device, sn:"$1
|
||||
fi
|
||||
exit 0
|
||||
@ -1,189 +0,0 @@
|
||||
/* Default STM32F4xx linker script.
|
||||
*
|
||||
* Modify memory sections according to the targeted platform.
|
||||
*/
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = ${FLASH_START}, LENGTH = ${FLASH_SIZE}
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = ${RAM_SIZE}
|
||||
CCMRAM (rw) : ORIGIN = 0x10000000, LENGTH = ${CCMRAM_SIZE}
|
||||
}
|
||||
|
||||
/* Reset_Handler : Entry of reset handler */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/* Linker script to place sections and symbol values. Should be used together
|
||||
* with other linker script that defines memory regions FLASH and RAM.
|
||||
* It defines following symbols, which code can use without definition.
|
||||
* __exidx_start
|
||||
* __exidx_end
|
||||
* __etext
|
||||
* _sdata
|
||||
* __preinit_array_start
|
||||
* __preinit_array_end
|
||||
* __init_array_start
|
||||
* __init_array_end
|
||||
* __fini_array_start
|
||||
* __fini_array_end
|
||||
* _edata
|
||||
* _sbss
|
||||
* __bss_start__
|
||||
* __bss_end__
|
||||
* _ebss
|
||||
* __end__
|
||||
* end
|
||||
* __HeapLimit
|
||||
* __StackLimit
|
||||
* __StackTop
|
||||
* _sidata
|
||||
* _siccmram
|
||||
*/
|
||||
|
||||
_estack = ORIGIN(RAM) + LENGTH(RAM);
|
||||
_Min_Heap_Size = ${HEAP_SIZE};
|
||||
_Min_Stack_Size = ${STACK_SIZE};
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.text :
|
||||
{
|
||||
KEEP(*(.isr_vector))
|
||||
*(.text*)
|
||||
|
||||
KEEP(*(.init))
|
||||
KEEP(*(.fini))
|
||||
|
||||
/* .ctors */
|
||||
*crtbegin.o(.ctors)
|
||||
*crtbegin?.o(.ctors)
|
||||
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
|
||||
*(SORT(.ctors.*))
|
||||
*(.ctors)
|
||||
|
||||
/* .dtors */
|
||||
*crtbegin.o(.dtors)
|
||||
*crtbegin?.o(.dtors)
|
||||
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
|
||||
*(SORT(.dtors.*))
|
||||
*(.dtors)
|
||||
|
||||
*(.rodata*)
|
||||
|
||||
KEEP(*(.eh_frame*))
|
||||
} > FLASH
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
} > FLASH
|
||||
|
||||
__exidx_start = .;
|
||||
.ARM.exidx :
|
||||
{
|
||||
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
|
||||
} > FLASH
|
||||
__exidx_end = .;
|
||||
|
||||
__etext = .;
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = LOADADDR(.data);
|
||||
|
||||
.data : AT (__etext)
|
||||
{
|
||||
_sdata = .;
|
||||
*(vtable)
|
||||
*(.data*)
|
||||
|
||||
. = ALIGN(4);
|
||||
/* preinit data */
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP(*(.preinit_array))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
|
||||
. = ALIGN(4);
|
||||
/* init data */
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP(*(SORT(.init_array.*)))
|
||||
KEEP(*(.init_array))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
|
||||
|
||||
. = ALIGN(4);
|
||||
/* finit data */
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP(*(SORT(.fini_array.*)))
|
||||
KEEP(*(.fini_array))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
|
||||
KEEP(*(.jcr*))
|
||||
. = ALIGN(4);
|
||||
/* All data end */
|
||||
_edata = .;
|
||||
|
||||
} > RAM
|
||||
|
||||
_siccmram = LOADADDR(.ccmram);
|
||||
|
||||
/* CCM-RAM section
|
||||
*
|
||||
* IMPORTANT NOTE!
|
||||
* If initialized variables will be placed in this section,
|
||||
* the startup code needs to be modified to copy the init-values.
|
||||
*/
|
||||
.ccmram :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sccmram = .; /* create a global symbol at ccmram start */
|
||||
*(.ccmram)
|
||||
*(.ccmram*)
|
||||
|
||||
. = ALIGN(4);
|
||||
_eccmram = .; /* create a global symbol at ccmram end */
|
||||
} >CCMRAM AT> FLASH
|
||||
|
||||
.bss :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sbss = .;
|
||||
__bss_start__ = _sbss;
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = .;
|
||||
__bss_end__ = _ebss;
|
||||
} > RAM
|
||||
|
||||
.heap (COPY):
|
||||
{
|
||||
__end__ = .;
|
||||
PROVIDE(end = .);
|
||||
*(.heap*)
|
||||
__HeapLimit = .;
|
||||
} > RAM
|
||||
|
||||
/* .stack_dummy section doesn't contains any symbols. It is only
|
||||
* used for linker to calculate size of stack sections, and assign
|
||||
* values to stack symbols later */
|
||||
.stack_dummy (COPY):
|
||||
{
|
||||
*(.stack*)
|
||||
} > RAM
|
||||
|
||||
/* Set stack top to end of RAM, and stack limit move down by
|
||||
* size of stack_dummy section */
|
||||
__StackTop = ORIGIN(RAM) + LENGTH(RAM);
|
||||
__StackLimit = __StackTop - SIZEOF(.stack_dummy);
|
||||
PROVIDE(_estack = __StackTop);
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
/* Check if data + heap + stack exceeds RAM limit */
|
||||
ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed with stack")
|
||||
}
|
||||
Reference in New Issue
Block a user