NEW: release DJI Payload-SDK version 3.5
Signed-off-by: DJI-Martin <DJI-Martin@dji.com>
This commit is contained in:
@ -50,6 +50,7 @@ static const char *s_cameraManagerSampleSelectList[] = {
|
||||
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_INTERVAL_PHOTO] = "Shoot interval photo |",
|
||||
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_RECORD_VIDEO] = "Record video |",
|
||||
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_DOWNLOAD_AND_DELETE_MEDIA_FILE] = "Download and delete media file |",
|
||||
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_DOWNLOAD_FILE_LIST_BY_SLICES] = "Download file list by slices |",
|
||||
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_THERMOMETRY] = "Thermometry test |",
|
||||
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_GET_LIDAR_RANGING_INFO] = "Get lidar ranging info |",
|
||||
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_IR_CAMERA_ZOOM_PARAM] = "Set ir camera zoom param |",
|
||||
@ -120,8 +121,7 @@ void DjiUser_RunCameraManagerSample(void)
|
||||
if (posNum > 3 || posNum < 1) {
|
||||
USER_LOG_ERROR("Input mount position is invalid");
|
||||
continue;
|
||||
}
|
||||
else {
|
||||
} else {
|
||||
break;
|
||||
}
|
||||
}
|
||||
@ -140,15 +140,15 @@ void DjiUser_RunCameraManagerSample(void)
|
||||
return;
|
||||
}
|
||||
|
||||
sampleSelectNum = atoi(sampleSelectStr.c_str());
|
||||
sampleSelectNum = atoi(sampleSelectStr.c_str());
|
||||
|
||||
if (sampleSelectNum < 0 ||
|
||||
sampleSelectNum >= (int)E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_INDEX_MAX) {
|
||||
sampleSelectNum >= (int) E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_INDEX_MAX) {
|
||||
USER_LOG_ERROR("Input camera sample is invalid");
|
||||
continue;
|
||||
}
|
||||
|
||||
cameraSample = (E_DjiTestCameraManagerSampleSelect)sampleSelectNum;
|
||||
cameraSample = (E_DjiTestCameraManagerSampleSelect) sampleSelectNum;
|
||||
|
||||
cout << "Start test: position " << cameraMountPosition
|
||||
<< ", sample " << cameraSample << endl;
|
||||
|
@ -88,6 +88,7 @@ start:
|
||||
if (mountPosition == 'q') {
|
||||
return;
|
||||
}
|
||||
|
||||
if (mountPosition > '3' || mountPosition < '1') {
|
||||
USER_LOG_ERROR("Input mount position is invalid");
|
||||
goto start;
|
||||
@ -126,4 +127,4 @@ void DjiTest_GimbalManagerShowSampleSelectList(const char **SampleList, uint8_t
|
||||
std::cout << SampleList[i] << std::endl;
|
||||
}
|
||||
}
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
|
@ -48,4 +48,5 @@ void DjiUser_RunGimbalManagerSample(void);
|
||||
#endif
|
||||
|
||||
#endif // TEST_GIMBAL_ENTRY_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
|
||||
|
@ -1,4 +1,4 @@
|
||||
/**
|
||||
/**
|
||||
********************************************************************
|
||||
* @file test_perception_entry.cpp
|
||||
* @brief
|
||||
@ -358,13 +358,6 @@ static void *DjiTest_StereoImagesDisplayTask(void *arg)
|
||||
pack->gotData = false;
|
||||
osalHandler->MutexUnlock(pack->mutex);
|
||||
|
||||
/*! Using Opencv display here */
|
||||
if (strstr(nameStr, "_l")) {
|
||||
cv::moveWindow(nameStr, 200, 0);
|
||||
} else {
|
||||
cv::moveWindow(nameStr, (200 + (int) pack->info.rawInfo.width), 0);
|
||||
}
|
||||
|
||||
if (i < USER_PERCEPTION_DIRECTION_NUM) {
|
||||
/*! Calculate frame rate */
|
||||
timeNow[i] = (double) cv::getTickCount();
|
||||
|
@ -98,6 +98,10 @@ T_DjiReturnCode Osal_MutexCreate(T_DjiMutexHandle *mutex)
|
||||
{
|
||||
int result;
|
||||
|
||||
if (!mutex) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
*mutex = malloc(sizeof(pthread_mutex_t));
|
||||
if (*mutex == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_MEMORY_ALLOC_FAILED;
|
||||
@ -118,7 +122,11 @@ T_DjiReturnCode Osal_MutexCreate(T_DjiMutexHandle *mutex)
|
||||
*/
|
||||
T_DjiReturnCode Osal_MutexDestroy(T_DjiMutexHandle mutex)
|
||||
{
|
||||
int result;
|
||||
int result = 0;
|
||||
|
||||
if (!mutex) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
result = pthread_mutex_destroy(mutex);
|
||||
if (result != 0) {
|
||||
@ -136,8 +144,13 @@ T_DjiReturnCode Osal_MutexDestroy(T_DjiMutexHandle mutex)
|
||||
*/
|
||||
T_DjiReturnCode Osal_MutexLock(T_DjiMutexHandle mutex)
|
||||
{
|
||||
int result = pthread_mutex_lock(mutex);
|
||||
int result = 0;
|
||||
|
||||
if (!mutex) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
result = pthread_mutex_lock(mutex);
|
||||
if (result != 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
@ -152,8 +165,13 @@ T_DjiReturnCode Osal_MutexLock(T_DjiMutexHandle mutex)
|
||||
*/
|
||||
T_DjiReturnCode Osal_MutexUnlock(T_DjiMutexHandle mutex)
|
||||
{
|
||||
int result = pthread_mutex_unlock(mutex);
|
||||
int result = 0;
|
||||
|
||||
if (!mutex) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
result = pthread_mutex_unlock(mutex);
|
||||
if (result != 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
@ -308,6 +326,14 @@ T_DjiReturnCode Osal_GetTimeUs(uint64_t *us)
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode Osal_GetRandomNum(uint16_t *randomNum)
|
||||
{
|
||||
srand(time(NULL));
|
||||
*randomNum = random() % 65535;
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
void *Osal_Malloc(uint32_t size)
|
||||
{
|
||||
return malloc(size);
|
||||
|
@ -65,6 +65,7 @@ T_DjiReturnCode Osal_SemaphorePost(T_DjiSemaHandle semaphore);
|
||||
|
||||
T_DjiReturnCode Osal_GetTimeMs(uint32_t *ms);
|
||||
T_DjiReturnCode Osal_GetTimeUs(uint64_t *us);
|
||||
T_DjiReturnCode Osal_GetRandomNum(uint16_t *randomNum);
|
||||
|
||||
void *Osal_Malloc(uint32_t size);
|
||||
void Osal_Free(void *ptr);
|
||||
|
@ -72,7 +72,8 @@ T_DjiReturnCode Osal_Socket(E_DjiSocketMode mode, T_DjiSocketHandle *socketHandl
|
||||
goto out;
|
||||
}
|
||||
|
||||
if (setsockopt(socketHandleStruct->socketFd, SOL_SOCKET, SO_RCVBUF, &rcvBufSize, optlen) < 0) {
|
||||
if (setsockopt(socketHandleStruct->socketFd, SOL_SOCKET, SO_RCVBUF, &rcvBufSize, optlen) < 0)
|
||||
{
|
||||
goto out;
|
||||
}
|
||||
} else if (mode == DJI_SOCKET_MODE_TCP) {
|
||||
@ -86,7 +87,6 @@ T_DjiReturnCode Osal_Socket(E_DjiSocketMode mode, T_DjiSocketHandle *socketHandl
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
|
||||
out:
|
||||
|
||||
close(socketHandleStruct->socketFd);
|
||||
free(socketHandleStruct);
|
||||
|
||||
|
@ -2,15 +2,24 @@ cmake_minimum_required(VERSION 3.5)
|
||||
project(dji_sdk_demo_linux_cxx CXX)
|
||||
|
||||
set(CMAKE_C_FLAGS "-pthread -std=gnu99")
|
||||
set(CMAKE_CXX_FLAGS "-std=c++11 -pthread")
|
||||
set(CMAKE_EXE_LINKER_FLAGS "-pthread")
|
||||
set(CMAKE_C_COMPILER "gcc")
|
||||
set(CMAKE_CXX_COMPILER "g++")
|
||||
add_definitions(-D_GNU_SOURCE)
|
||||
|
||||
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")
|
||||
if (MEMORY_LEAK_CHECK_ON MATCHES TRUE)
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fsanitize=leak")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fsanitize=leak")
|
||||
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -lasan")
|
||||
endif ()
|
||||
|
||||
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 -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)
|
||||
|
@ -77,14 +77,14 @@ Application::~Application()
|
||||
void Application::DjiUser_SetupEnvironment()
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiOsalHandler osalHandler;
|
||||
T_DjiHalUartHandler uartHandler;
|
||||
T_DjiHalUsbBulkHandler usbBulkHandler;
|
||||
T_DjiOsalHandler osalHandler = {0};
|
||||
T_DjiHalUartHandler uartHandler = {0};
|
||||
T_DjiHalUsbBulkHandler usbBulkHandler = {0};
|
||||
T_DjiLoggerConsole printConsole;
|
||||
T_DjiLoggerConsole localRecordConsole;
|
||||
T_DjiFileSystemHandler fileSystemHandler;
|
||||
T_DjiSocketHandler socketHandler;
|
||||
T_DjiHalNetworkHandler networkHandler;
|
||||
T_DjiFileSystemHandler fileSystemHandler = {0};
|
||||
T_DjiSocketHandler socketHandler {0};
|
||||
T_DjiHalNetworkHandler networkHandler = {0};
|
||||
|
||||
networkHandler.NetworkInit = HalNetWork_Init;
|
||||
networkHandler.NetworkDeInit = HalNetWork_DeInit;
|
||||
@ -117,6 +117,7 @@ void Application::DjiUser_SetupEnvironment()
|
||||
osalHandler.Free = Osal_Free;
|
||||
osalHandler.GetTimeMs = Osal_GetTimeMs;
|
||||
osalHandler.GetTimeUs = Osal_GetTimeUs;
|
||||
osalHandler.GetRandomNum = Osal_GetRandomNum;
|
||||
|
||||
printConsole.func = DjiUser_PrintConsole;
|
||||
printConsole.consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO;
|
||||
|
@ -30,7 +30,6 @@
|
||||
#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>
|
||||
|
@ -62,17 +62,19 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
ret = libusb_init(NULL);
|
||||
if (ret < 0) {
|
||||
USER_LOG_ERROR("init usb bulk failed, errno = %d", ret);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
handle = libusb_open_device_with_vid_pid(NULL, usbBulkInfo.vid, usbBulkInfo.pid);
|
||||
if (handle == NULL) {
|
||||
if(handle == NULL) {
|
||||
USER_LOG_ERROR("open usb device failed");
|
||||
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");
|
||||
USER_LOG_ERROR("libusb claim interface failed, errno = %d", ret);
|
||||
libusb_close(handle);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
@ -115,6 +117,7 @@ T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle)
|
||||
{
|
||||
struct libusb_device_handle *handle = NULL;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
int32_t ret;
|
||||
|
||||
if (usbBulkHandle == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
@ -124,8 +127,11 @@ T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle)
|
||||
|
||||
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
libusb_release_interface(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum);
|
||||
osalHandler->TaskSleepMs(100);
|
||||
ret = libusb_release_interface(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum);
|
||||
if(ret != 0) {
|
||||
USER_LOG_ERROR("release usb bulk interface failed, errno = %d", ret);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
libusb_exit(NULL);
|
||||
#endif
|
||||
} else {
|
||||
|
@ -1,15 +1,15 @@
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
project(dji_sdk_demo_on_jeston_cxx CXX)
|
||||
project(dji_sdk_demo_on_jetson_cxx CXX)
|
||||
|
||||
set(CMAKE_C_FLAGS "-pthread -std=gnu99")
|
||||
set(CMAKE_CXX_FLAGS "-std=c++11 -pthread")
|
||||
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_CXX_FLAGS "${CMAKE_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 ()
|
||||
@ -17,7 +17,7 @@ endif ()
|
||||
include_directories(../../../module_sample)
|
||||
include_directories(../../../../sample_c/module_sample)
|
||||
include_directories(../common)
|
||||
include_directories(../nvidia_jeston/application)
|
||||
include_directories(../nvidia_jetson/application)
|
||||
|
||||
file(GLOB_RECURSE MODULE_SAMPLE_SRC
|
||||
../../../module_sample/liveview/*.c*
|
||||
@ -57,9 +57,11 @@ if (OpenCV_FOUND)
|
||||
execute_process(COMMAND opencv_version OUTPUT_VARIABLE OPENCV_VERSION)
|
||||
if (${OPENCV_VERSION} STRLESS "4.0.0")
|
||||
add_definitions(-DOPEN_CV_VERSION_3)
|
||||
else()
|
||||
|
||||
else ()
|
||||
add_definitions(-DOPEN_CV_VERSION_4)
|
||||
endif()
|
||||
|
||||
endif ()
|
||||
else ()
|
||||
message(STATUS "Did not find OpenCV in the system, image data is inside RecvContainer as raw data")
|
||||
endif ()
|
||||
@ -69,8 +71,6 @@ 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)
|
||||
include_directories(${FFMPEG_INCLUDE_DIR})
|
||||
|
||||
EXECUTE_PROCESS(COMMAND ffmpeg -version
|
||||
OUTPUT_VARIABLE ffmpeg_version_psdk_libput
|
||||
@ -87,6 +87,8 @@ 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)
|
@ -77,14 +77,14 @@ Application::~Application()
|
||||
void Application::DjiUser_SetupEnvironment()
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiOsalHandler osalHandler;
|
||||
T_DjiHalUartHandler uartHandler;
|
||||
T_DjiHalUsbBulkHandler usbBulkHandler;
|
||||
T_DjiOsalHandler osalHandler = {0};
|
||||
T_DjiHalUartHandler uartHandler = {0};
|
||||
T_DjiHalUsbBulkHandler usbBulkHandler = {0};
|
||||
T_DjiLoggerConsole printConsole;
|
||||
T_DjiLoggerConsole localRecordConsole;
|
||||
T_DjiFileSystemHandler fileSystemHandler;
|
||||
T_DjiSocketHandler socketHandler;
|
||||
T_DjiHalNetworkHandler networkHandler;
|
||||
T_DjiFileSystemHandler fileSystemHandler = {0};
|
||||
T_DjiSocketHandler socketHandler = {0};
|
||||
T_DjiHalNetworkHandler networkHandler = {0};
|
||||
|
||||
networkHandler.NetworkInit = HalNetWork_Init;
|
||||
networkHandler.NetworkDeInit = HalNetWork_DeInit;
|
||||
@ -117,6 +117,7 @@ void Application::DjiUser_SetupEnvironment()
|
||||
osalHandler.Free = Osal_Free;
|
||||
osalHandler.GetTimeMs = Osal_GetTimeMs;
|
||||
osalHandler.GetTimeUs = Osal_GetTimeUs;
|
||||
osalHandler.GetRandomNum = Osal_GetRandomNum,
|
||||
|
||||
printConsole.func = DjiUser_PrintConsole;
|
||||
printConsole.consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO;
|
@ -186,7 +186,8 @@ T_DjiReturnCode DjiTest_CameraEmuMediaStartService(void)
|
||||
|
||||
UtilBuffer_Init(&s_mediaPlayCommandBufferHandler, s_mediaPlayCommandBuffer, sizeof(s_mediaPlayCommandBuffer));
|
||||
|
||||
if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK) {
|
||||
if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK) {
|
||||
returnCode = DjiPayloadCamera_RegMediaDownloadPlaybackHandler(&s_psdkCameraMedia);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("psdk camera media function init error.");
|
||||
|
@ -72,6 +72,7 @@ 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_CameraManagerMediaDownloadFileListBySlices(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);
|
||||
@ -1071,8 +1072,8 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition,
|
||||
"error code: 0x%08X\r\n", mountPosition, returnCode);
|
||||
goto exitCameraModule;
|
||||
}
|
||||
USER_LOG_INFO("Sleep 4s...");
|
||||
osalHandler->TaskSleepMs(4000);
|
||||
USER_LOG_INFO("Sleep 8s...");
|
||||
osalHandler->TaskSleepMs(8000);
|
||||
|
||||
returnCode = DjiTest_CameraManagerOpticalZoom(mountPosition, DJI_CAMERA_ZOOM_DIRECTION_OUT, 5);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -1195,6 +1196,15 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition,
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
|
||||
case E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_DOWNLOAD_FILE_LIST_BY_SLICES: {
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
DjiTest_CameraManagerMediaDownloadFileListBySlices(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) {
|
||||
@ -1353,6 +1363,77 @@ static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_Dj
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadFileListBySlices(E_DjiMountPosition position)
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
uint16_t downloadCount = 0;
|
||||
T_DjiCameraManagerSliceConfig sliceConfig = {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);
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
sliceConfig.countPerSlice = DJI_CAMERA_MANAGER_FILE_LIST_COUNT_ALL_PER_SLICE;
|
||||
sliceConfig.sliceStartIndex = 0;
|
||||
|
||||
returnCode = DjiCameraManager_DownloadFileListBySlices(position, sliceConfig, &s_meidaFileList);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Download file list failed, error code: 0x%08X.", returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
if (s_meidaFileList.totalCount > 0) {
|
||||
downloadCount = s_meidaFileList.totalCount;
|
||||
printf(
|
||||
"\033[1;33;40m -> Download file list finished, total file count is %d, the following %d is list details: \033[0m\r\n",
|
||||
s_meidaFileList.totalCount, downloadCount);
|
||||
for (int i = 0; i < downloadCount; ++i) {
|
||||
if (s_meidaFileList.fileListInfo[i].fileSize < 1 * 1024 * 1024) {
|
||||
printf(
|
||||
"\033[1;32;40m ### Media file_%03d name: %s, index: %d, time:%04d-%02d-%02d_%02d:%02d:%02d, size: %.2f KB, type: %d \033[0m\r\n",
|
||||
i, s_meidaFileList.fileListInfo[i].fileName,
|
||||
s_meidaFileList.fileListInfo[i].fileIndex,
|
||||
s_meidaFileList.fileListInfo[i].createTime.year,
|
||||
s_meidaFileList.fileListInfo[i].createTime.month,
|
||||
s_meidaFileList.fileListInfo[i].createTime.day,
|
||||
s_meidaFileList.fileListInfo[i].createTime.hour,
|
||||
s_meidaFileList.fileListInfo[i].createTime.minute,
|
||||
s_meidaFileList.fileListInfo[i].createTime.second,
|
||||
(dji_f32_t) s_meidaFileList.fileListInfo[i].fileSize / 1024,
|
||||
s_meidaFileList.fileListInfo[i].type);
|
||||
} else {
|
||||
printf(
|
||||
"\033[1;32;40m ### Media file_%03d name: %s, index: %d, time:%04d-%02d-%02d_%02d:%02d:%02d, size: %.2f MB, type: %d \033[0m\r\n",
|
||||
i, s_meidaFileList.fileListInfo[i].fileName,
|
||||
s_meidaFileList.fileListInfo[i].fileIndex,
|
||||
s_meidaFileList.fileListInfo[i].createTime.year,
|
||||
s_meidaFileList.fileListInfo[i].createTime.month,
|
||||
s_meidaFileList.fileListInfo[i].createTime.day,
|
||||
s_meidaFileList.fileListInfo[i].createTime.hour,
|
||||
s_meidaFileList.fileListInfo[i].createTime.minute,
|
||||
s_meidaFileList.fileListInfo[i].createTime.second,
|
||||
(dji_f32_t) s_meidaFileList.fileListInfo[i].fileSize / (1024 * 1024),
|
||||
s_meidaFileList.fileListInfo[i].type);
|
||||
}
|
||||
}
|
||||
printf("\r\n");
|
||||
|
||||
returnCode = DjiCameraManager_DownloadFileByIndex(position, s_meidaFileList.fileListInfo[0].fileIndex);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Download media file by index failed, error code: 0x%08X.", returnCode);
|
||||
}
|
||||
|
||||
} else {
|
||||
USER_LOG_WARN("Media file is not existed in sdcard.\r\n");
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiTest_CameraManagerDownloadFileDataCallback(T_DjiDownloadFilePacketInfo packetInfo,
|
||||
const uint8_t *data, uint16_t len)
|
||||
{
|
||||
@ -1371,7 +1452,8 @@ 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, s_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;
|
||||
|
@ -52,6 +52,7 @@ 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_DOWNLOAD_FILE_LIST_BY_SLICES,
|
||||
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,
|
||||
|
@ -60,7 +60,6 @@ T_DjiReturnCode DjiTest_DataTransmissionStartService(void)
|
||||
char ipAddr[DJI_IP_ADDR_STR_SIZE_MAX];
|
||||
uint16_t port;
|
||||
|
||||
|
||||
djiStat = DjiLowSpeedDataChannel_Init();
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("init data transmission module error.");
|
||||
@ -124,6 +123,25 @@ T_DjiReturnCode DjiTest_DataTransmissionStartService(void)
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode DjiTest_DataTransmissionStopService(void)
|
||||
{
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
T_DjiReturnCode returnCode;
|
||||
|
||||
if (osalHandler->TaskDestroy(s_userDataTransmissionThread) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("user data transmission task destroy error.");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
}
|
||||
|
||||
returnCode = DjiLowSpeedDataChannel_DeInit();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("deinit data transmission module error.");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
#ifndef __CC_ARM
|
||||
#pragma GCC diagnostic push
|
||||
|
@ -41,6 +41,7 @@ extern "C" {
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
T_DjiReturnCode DjiTest_DataTransmissionStartService(void);
|
||||
T_DjiReturnCode DjiTest_DataTransmissionStopService(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
@ -126,7 +126,7 @@ T_DjiReturnCode DjiTest_FcSubscriptionRunSample(void)
|
||||
}
|
||||
|
||||
USER_LOG_INFO("--> Step 2: Subscribe the topics of quaternion, velocity and gps position");
|
||||
djiStat = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_QUATERNION, DJI_DATA_SUBSCRIPTION_TOPIC_1_HZ,
|
||||
djiStat = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_QUATERNION, DJI_DATA_SUBSCRIPTION_TOPIC_50_HZ,
|
||||
DjiTest_FcSubscriptionReceiveQuaternionCallback);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Subscribe topic quaternion error.");
|
||||
|
@ -186,7 +186,10 @@ T_DjiReturnCode DjiTest_FlightControlInit(void)
|
||||
DJI_DATA_SUBSCRIPTION_TOPIC_50_HZ,
|
||||
NULL);
|
||||
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
if (returnCode == DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
} else if (returnCode == DJI_ERROR_SUBSCRIPTION_MODULE_CODE_TOPIC_DUPLICATE) {
|
||||
USER_LOG_WARN("Subscribe topic quaternion duplicate");
|
||||
} else {
|
||||
USER_LOG_ERROR("Subscribe topic quaternion failed,error code:0x%08llX", returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
@ -703,7 +706,8 @@ void DjiTest_FlightControlSetGetParamSample()
|
||||
DjiTest_WidgetLogAppend("--> Step 3: Turn on horizontal radar obstacle avoidance");
|
||||
if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30 ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30T) {
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30T ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK) {
|
||||
returnCode = DjiFlightController_SetHorizontalRadarObstacleAvoidanceEnableStatus(
|
||||
DJI_FLIGHT_CONTROLLER_ENABLE_OBSTACLE_AVOIDANCE);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -717,7 +721,8 @@ void DjiTest_FlightControlSetGetParamSample()
|
||||
DjiTest_WidgetLogAppend("--> Step 4: Get horizontal radar obstacle avoidance status\r\n");
|
||||
if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30 ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30T) {
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30T ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK) {
|
||||
returnCode = DjiFlightController_GetHorizontalRadarObstacleAvoidanceEnableStatus(
|
||||
&horizontalRadarObstacleAvoidanceStatus);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -756,7 +761,8 @@ void DjiTest_FlightControlSetGetParamSample()
|
||||
DjiTest_WidgetLogAppend("--> Step 7: Turn on upwards radar obstacle avoidance.");
|
||||
if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30 ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30T) {
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30T ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK) {
|
||||
returnCode = DjiFlightController_SetUpwardsRadarObstacleAvoidanceEnableStatus(
|
||||
DJI_FLIGHT_CONTROLLER_ENABLE_OBSTACLE_AVOIDANCE);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -770,7 +776,8 @@ void DjiTest_FlightControlSetGetParamSample()
|
||||
DjiTest_WidgetLogAppend("--> Step 8: Get upwards radar obstacle avoidance status\r\n");
|
||||
if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30 ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30T) {
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30T ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK) {
|
||||
returnCode = DjiFlightController_GetUpwardsRadarObstacleAvoidanceEnableStatus(
|
||||
&upwardsRadarObstacleAvoidanceStatus);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -846,7 +853,8 @@ void DjiTest_FlightControlSetGetParamSample()
|
||||
s_osalHandler->TaskSleepMs(1000);
|
||||
|
||||
/*! Set rc lost action */
|
||||
if (aircraftInfoBaseInfo.aircraftType != DJI_AIRCRAFT_TYPE_M300_RTK) {
|
||||
if (aircraftInfoBaseInfo.aircraftType != DJI_AIRCRAFT_TYPE_M300_RTK &&
|
||||
aircraftInfoBaseInfo.aircraftType != DJI_AIRCRAFT_TYPE_M350_RTK) {
|
||||
USER_LOG_INFO("--> Step 15: Set rc lost action");
|
||||
DjiTest_WidgetLogAppend("--> Step 15: Set rc lost action");
|
||||
returnCode = DjiFlightController_SetRCLostAction(DJI_FLIGHT_CONTROLLER_RC_LOST_ACTION_GOHOME);
|
||||
|
@ -35,6 +35,7 @@
|
||||
#define PAYLOAD_GIMBAL_EMU_TASK_STACK_SIZE (2048)
|
||||
#define PAYLOAD_GIMBAL_TASK_FREQ 1000
|
||||
#define PAYLOAD_GIMBAL_CALIBRATION_TIME_MS 2000
|
||||
#define PAYLOAD_GIMBAL_MIN_ACTION_TIME 5
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
typedef enum {
|
||||
@ -389,10 +390,14 @@ static void *UserGimbal_Task(void *arg)
|
||||
|
||||
djiStat = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_QUATERNION, DJI_DATA_SUBSCRIPTION_TOPIC_10_HZ,
|
||||
NULL);
|
||||
if (djiStat == DJI_ERROR_SUBSCRIPTION_MODULE_CODE_TOPIC_DUPLICATE) {
|
||||
USER_LOG_DEBUG("Subscribe topic quaternion duplicate.");
|
||||
} else if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Subscribe topic quaternion error.");
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
if (djiStat == DJI_ERROR_SUBSCRIPTION_MODULE_CODE_TOPIC_DUPLICATE) {
|
||||
USER_LOG_WARN("Subscribe topic quaternion duplicate.");
|
||||
} else {
|
||||
USER_LOG_ERROR("Subscribe topic quaternion error.");
|
||||
}
|
||||
} else {
|
||||
USER_LOG_DEBUG("Subscribe topic quaternion success.");
|
||||
}
|
||||
|
||||
while (1) {
|
||||
@ -1077,6 +1082,11 @@ DjiTest_GimbalCalculateSpeed(T_DjiAttitude3d originalAttitude, T_DjiAttitude3d t
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
if (actionTime == 0) {
|
||||
USER_LOG_WARN("Input action time is zero, now used max speed to rotate.");
|
||||
actionTime = PAYLOAD_GIMBAL_MIN_ACTION_TIME;
|
||||
}
|
||||
|
||||
pitchSpeedTemp = (float) (targetAttitude.pitch - originalAttitude.pitch) / (float) actionTime * 100;
|
||||
rollSpeedTemp = (float) (targetAttitude.roll - originalAttitude.roll) / (float) actionTime * 100;
|
||||
yawSpeedTemp = (float) (targetAttitude.yaw - originalAttitude.yaw) / (float) actionTime * 100;
|
||||
|
@ -45,7 +45,7 @@ typedef struct {
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
static const T_DjiTestGimbalActionList s_rotationActionList[] =
|
||||
{
|
||||
{
|
||||
{.action = DJI_TEST_GIMBAL_RESET},
|
||||
{.action = DJI_TEST_GIMBAL_ROTATION, .rotation.rotationMode = DJI_GIMBAL_ROTATION_MODE_RELATIVE_ANGLE, 30, 0, 0, 0.2},
|
||||
{.action = DJI_TEST_GIMBAL_ROTATION, .rotation.rotationMode = DJI_GIMBAL_ROTATION_MODE_RELATIVE_ANGLE, -30, 0, 0, 0.2},
|
||||
@ -63,7 +63,7 @@ static const T_DjiTestGimbalActionList s_rotationActionList[] =
|
||||
{.action = DJI_TEST_GIMBAL_ROTATION, .rotation.rotationMode = DJI_GIMBAL_ROTATION_MODE_ABSOLUTE_ANGLE, -60, 0, 0, 0.5},
|
||||
{.action = DJI_TEST_GIMBAL_ROTATION, .rotation.rotationMode = DJI_GIMBAL_ROTATION_MODE_ABSOLUTE_ANGLE, -30, 0, 0, 0.5},
|
||||
{.action = DJI_TEST_GIMBAL_RESET},
|
||||
};
|
||||
};
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
|
||||
@ -151,6 +151,4 @@ out:
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
|
@ -52,6 +52,7 @@ 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},
|
||||
};
|
||||
static bool s_hmsServiceRunFlag = false;
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
static T_DjiReturnCode DjiTest_HmsInit(void);
|
||||
@ -169,6 +170,8 @@ T_DjiReturnCode DjiTest_HmsStartService(void)
|
||||
DjiHms_InjectHmsErrorCode(0x1E020000, DJI_HMS_ERROR_LEVEL_FATAL);
|
||||
#endif
|
||||
|
||||
s_hmsServiceRunFlag = true;
|
||||
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
@ -193,6 +196,10 @@ static T_DjiReturnCode DjiTest_HmsInit(void)
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
if (s_hmsServiceRunFlag == true) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
return DjiHms_Init();
|
||||
}
|
||||
|
||||
@ -207,6 +214,10 @@ static T_DjiReturnCode DjiTest_HmsDeInit(void)
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
if (s_hmsServiceRunFlag == true) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
return DjiHms_DeInit();
|
||||
}
|
||||
|
||||
|
@ -87,7 +87,8 @@ T_DjiReturnCode DjiTest_PowerManagementStartService(void)
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
if (baseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK &&
|
||||
if ((baseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK ||
|
||||
baseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK) &&
|
||||
(baseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 ||
|
||||
baseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_XPORT)) {
|
||||
// apply high power
|
||||
@ -130,6 +131,19 @@ T_DjiReturnCode DjiTest_PowerManagementStartService(void)
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode DjiTest_PowerManagementStopService(void)
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
|
||||
returnCode = DjiPowerManagement_DeInit();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("power management deinit error: 0x%08llX.", returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
static T_DjiReturnCode DjiTest_PowerOffNotificationCallback(bool *powerOffPreparationFlag)
|
||||
{
|
||||
|
@ -46,6 +46,7 @@ typedef struct {
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
T_DjiReturnCode DjiTest_PowerManagementStartService(void);
|
||||
T_DjiReturnCode DjiTest_PowerManagementStopService(void);
|
||||
T_DjiReturnCode DjiTest_RegApplyHighPowerHandler(T_DjiTestApplyHighPowerHandler *applyHighPowerHandler);
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
@ -29,6 +29,7 @@
|
||||
#include "dji_logger.h"
|
||||
#include "dji_waypoint_v3.h"
|
||||
#include "waypoint_file_c/waypoint_v3_test_file_kmz.h"
|
||||
#include "dji_fc_subscription.h"
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define DJI_TEST_WAYPOINT_V3_KMZ_FILE_PATH_LEN_MAX (256)
|
||||
@ -47,6 +48,9 @@ T_DjiReturnCode DjiTest_WaypointV3RunSample(void)
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
T_DjiFcSubscriptionFlightStatus flightStatus = 0;
|
||||
T_DjiDataTimestamp flightStatusTimestamp = {0};
|
||||
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
FILE *kmzFile = NULL;
|
||||
uint32_t kmzFileSize = 0;
|
||||
@ -94,25 +98,25 @@ T_DjiReturnCode DjiTest_WaypointV3RunSample(void)
|
||||
returnCode = UtilFile_GetFileSize(kmzFile, &kmzFileSize);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Get kmz file size failed.");
|
||||
goto out;
|
||||
goto close_file;
|
||||
}
|
||||
|
||||
kmzFileBuf = osalHandler->Malloc(kmzFileSize);
|
||||
if (kmzFileBuf == NULL) {
|
||||
USER_LOG_ERROR("Malloc kmz file buf error.");
|
||||
goto out;
|
||||
goto close_file;
|
||||
}
|
||||
|
||||
readLen = fread(kmzFileBuf, 1, kmzFileSize, kmzFile);
|
||||
if (readLen != kmzFileSize) {
|
||||
USER_LOG_ERROR("Read kmz file data failed.");
|
||||
goto out;
|
||||
goto close_file;
|
||||
}
|
||||
|
||||
returnCode = DjiWaypointV3_UploadKmzFile(kmzFileBuf, kmzFileSize);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Upload kmz file failed.");
|
||||
goto out;
|
||||
goto close_file;
|
||||
}
|
||||
|
||||
osalHandler->Free(kmzFileBuf);
|
||||
@ -129,14 +133,43 @@ T_DjiReturnCode DjiTest_WaypointV3RunSample(void)
|
||||
returnCode = DjiWaypointV3_Action(DJI_WAYPOINT_V3_ACTION_START);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Execute start action failed.");
|
||||
goto close_file;
|
||||
}
|
||||
|
||||
osalHandler->TaskSleepMs(2000);
|
||||
|
||||
close_file:
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
returnCode = fclose(kmzFile);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Close KMZ file failed.");
|
||||
}
|
||||
kmzFile = NULL;
|
||||
#endif
|
||||
|
||||
returnCode = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_STATUS_FLIGHT,
|
||||
DJI_DATA_SUBSCRIPTION_TOPIC_10_HZ,
|
||||
NULL);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Subscribe topic flight status failed, error code:0x%08llX", returnCode);
|
||||
goto out;
|
||||
}
|
||||
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
fclose(kmzFile);
|
||||
#endif
|
||||
do {
|
||||
osalHandler->TaskSleepMs(2000);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
returnCode = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_STATUS_FLIGHT,
|
||||
(uint8_t *) &flightStatus,
|
||||
sizeof(T_DjiFcSubscriptionFlightStatus),
|
||||
&flightStatusTimestamp);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Get value of topic flight status failed, error code:0x%08llX", returnCode);
|
||||
}
|
||||
|
||||
USER_LOG_INFO("flight status: %d", flightStatus);
|
||||
} while(flightStatus == DJI_FC_SUBSCRIPTION_FLIGHT_STATUS_IN_AIR);
|
||||
|
||||
USER_LOG_INFO("The aircraft is on the ground now.");
|
||||
|
||||
out:
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
@ -145,7 +178,7 @@ out:
|
||||
}
|
||||
#endif
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
return DjiWaypointV3_DeInit();
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
|
@ -163,6 +163,7 @@ T_DjiReturnCode DjiTest_WidgetSpeakerStartService(void)
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
|
||||
static uint32_t DjiTest_GetVoicePlayProcessId(void)
|
||||
{
|
||||
FILE *fp;
|
||||
@ -220,21 +221,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) {
|
||||
USER_LOG_ERROR("failed to open input file: %s\n", strerror(errno));
|
||||
fprintf(stderr, "failed to open input file: %s\n", strerror(errno));
|
||||
return EXIT_FAILURE;
|
||||
}
|
||||
|
||||
fout = fopen(WIDGET_SPEAKER_AUDIO_PCM_FILE_NAME, "w");
|
||||
if (fout == NULL) {
|
||||
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;
|
||||
fprintf(stderr, "failed to create decoder: %s\n", opus_strerror(err));
|
||||
goto close_fin;
|
||||
}
|
||||
|
||||
fout = fopen(WIDGET_SPEAKER_AUDIO_PCM_FILE_NAME, "w");
|
||||
if (fout == NULL) {
|
||||
fprintf(stderr, "failed to open output file: %s\n", strerror(errno));
|
||||
goto close_fin;
|
||||
}
|
||||
|
||||
while (1) {
|
||||
@ -254,8 +255,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) {
|
||||
USER_LOG_ERROR("decoder failed: %s\n", opus_strerror(frame_size));
|
||||
goto decode_data_failed;
|
||||
fprintf(stderr, "decoder failed: %s\n", opus_strerror(frame_size));
|
||||
goto close_fout;
|
||||
}
|
||||
|
||||
USER_LOG_DEBUG("decode data to file: %d\r\n", frame_size * WIDGET_SPEAKER_AUDIO_OPUS_CHANNELS);
|
||||
@ -278,8 +279,18 @@ create_decoder_failed:
|
||||
open_pcm_audio_failed:
|
||||
fclose(fin);
|
||||
#endif
|
||||
return EXIT_SUCCESS;
|
||||
|
||||
#ifdef OPUS_INSTALLED
|
||||
close_fout:
|
||||
fclose(fout);
|
||||
|
||||
close_fin:
|
||||
fclose(fin);
|
||||
|
||||
return EXIT_FAILURE;
|
||||
#endif
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiTest_PlayAudioData(void)
|
||||
@ -364,7 +375,7 @@ static T_DjiReturnCode DjiTest_CheckFileMd5Sum(const char *path, uint8_t *buf, u
|
||||
uint32_t readFileTotalSize = 0;
|
||||
uint16_t readLen;
|
||||
T_DjiReturnCode returnCode;
|
||||
uint8_t readBuf[1024];
|
||||
uint8_t readBuf[1024] = {0};
|
||||
uint8_t md5Sum[16] = {0};
|
||||
FILE *file = NULL;;
|
||||
|
||||
@ -407,6 +418,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)
|
||||
@ -628,6 +640,7 @@ static T_DjiReturnCode ReceiveTtsData(E_DjiWidgetTransmitDataEvent event,
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
if (s_ttsFile != NULL) {
|
||||
fclose(s_ttsFile);
|
||||
s_ttsFile = NULL;
|
||||
}
|
||||
|
||||
returnCode = DjiTest_CheckFileMd5Sum(WIDGET_SPEAKER_TTS_FILE_NAME, buf, size);
|
||||
@ -685,6 +698,7 @@ static T_DjiReturnCode ReceiveAudioData(E_DjiWidgetTransmitDataEvent event,
|
||||
USER_LOG_INFO("Close voice file.");
|
||||
if (s_audioFile != NULL) {
|
||||
fclose(s_audioFile);
|
||||
s_audioFile = NULL;
|
||||
}
|
||||
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
|
@ -55,6 +55,13 @@
|
||||
#define WIDGET_LOG_STRING_MAX_SIZE (40)
|
||||
#define WIDGET_LOG_LINE_MAX_NUM (5)
|
||||
|
||||
#define DJI_HMS_ERROR_CODE_VALUE0 0x1E020000
|
||||
#define DJI_HMS_ERROR_CODE_VALUE1 0x1E020001
|
||||
#define DJI_HMS_ERROR_CODE_VALUE2 0x1E020002
|
||||
#define DJI_HMS_ERROR_CODE_VALUE3 0x1E020003
|
||||
#define DJI_HMS_ERROR_CODE_VALUE4 0x1E020004
|
||||
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
typedef enum {
|
||||
E_DJI_SAMPLE_INDEX_FC_SUBSCRIPTION = 0,
|
||||
@ -86,7 +93,6 @@ typedef enum {
|
||||
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;
|
||||
|
||||
@ -376,19 +382,19 @@ static void *DjiTest_WidgetInteractionTask(void *arg)
|
||||
if (s_isInjectErrcode == true && s_isEliminateErrcode == false) {
|
||||
switch (s_extensionPortErrcodeIndex) {
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX1:
|
||||
errorCode = 0x1E020000;
|
||||
errorCode = DJI_HMS_ERROR_CODE_VALUE0;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX2:
|
||||
errorCode = 0x1E020001;
|
||||
errorCode = DJI_HMS_ERROR_CODE_VALUE1;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX3:
|
||||
errorCode = 0x1E020002;
|
||||
errorCode = DJI_HMS_ERROR_CODE_VALUE2;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX4:
|
||||
errorCode = 0x1E020003;
|
||||
errorCode = DJI_HMS_ERROR_CODE_VALUE3;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX5:
|
||||
errorCode = 0x1E020004;
|
||||
errorCode = DJI_HMS_ERROR_CODE_VALUE4;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
@ -421,19 +427,19 @@ static void *DjiTest_WidgetInteractionTask(void *arg)
|
||||
if (s_isEliminateErrcode == true && s_isInjectErrcode == false) {
|
||||
switch (s_extensionPortErrcodeIndex) {
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX1:
|
||||
errorCode = 0x1E020000;
|
||||
errorCode = DJI_HMS_ERROR_CODE_VALUE0;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX2:
|
||||
errorCode = 0x1E020001;
|
||||
errorCode = DJI_HMS_ERROR_CODE_VALUE1;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX3:
|
||||
errorCode = 0x1E020002;
|
||||
errorCode = DJI_HMS_ERROR_CODE_VALUE2;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX4:
|
||||
errorCode = 0x1E020003;
|
||||
errorCode = DJI_HMS_ERROR_CODE_VALUE3;
|
||||
break;
|
||||
case E_DJI_HMS_ERROR_CODE_INDEX5:
|
||||
errorCode = 0x1E020004;
|
||||
errorCode = DJI_HMS_ERROR_CODE_VALUE4;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
|
@ -98,6 +98,10 @@ T_DjiReturnCode Osal_MutexCreate(T_DjiMutexHandle *mutex)
|
||||
{
|
||||
int result;
|
||||
|
||||
if (!mutex) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
*mutex = malloc(sizeof(pthread_mutex_t));
|
||||
if (*mutex == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_MEMORY_ALLOC_FAILED;
|
||||
@ -118,7 +122,11 @@ T_DjiReturnCode Osal_MutexCreate(T_DjiMutexHandle *mutex)
|
||||
*/
|
||||
T_DjiReturnCode Osal_MutexDestroy(T_DjiMutexHandle mutex)
|
||||
{
|
||||
int result;
|
||||
int result = 0;
|
||||
|
||||
if (!mutex) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
result = pthread_mutex_destroy(mutex);
|
||||
if (result != 0) {
|
||||
@ -136,8 +144,13 @@ T_DjiReturnCode Osal_MutexDestroy(T_DjiMutexHandle mutex)
|
||||
*/
|
||||
T_DjiReturnCode Osal_MutexLock(T_DjiMutexHandle mutex)
|
||||
{
|
||||
int result = pthread_mutex_lock(mutex);
|
||||
int result = 0;
|
||||
|
||||
if (!mutex) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
result = pthread_mutex_lock(mutex);
|
||||
if (result != 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
@ -152,8 +165,13 @@ T_DjiReturnCode Osal_MutexLock(T_DjiMutexHandle mutex)
|
||||
*/
|
||||
T_DjiReturnCode Osal_MutexUnlock(T_DjiMutexHandle mutex)
|
||||
{
|
||||
int result = pthread_mutex_unlock(mutex);
|
||||
int result = 0;
|
||||
|
||||
if (!mutex) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
result = pthread_mutex_unlock(mutex);
|
||||
if (result != 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
@ -308,6 +326,14 @@ T_DjiReturnCode Osal_GetTimeUs(uint64_t *us)
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode Osal_GetRandomNum(uint16_t *randomNum)
|
||||
{
|
||||
srand(time(NULL));
|
||||
*randomNum = random() % 65535;
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
void *Osal_Malloc(uint32_t size)
|
||||
{
|
||||
return malloc(size);
|
||||
|
@ -63,6 +63,7 @@ T_DjiReturnCode Osal_SemaphorePost(T_DjiSemaHandle semaphore);
|
||||
|
||||
T_DjiReturnCode Osal_GetTimeMs(uint32_t *ms);
|
||||
T_DjiReturnCode Osal_GetTimeUs(uint64_t *us);
|
||||
T_DjiReturnCode Osal_GetRandomNum(uint16_t *randomNum);
|
||||
|
||||
void *Osal_Malloc(uint32_t size);
|
||||
void Osal_Free(void *ptr);
|
||||
|
@ -46,7 +46,7 @@ typedef struct {
|
||||
T_DjiReturnCode Osal_Socket(E_DjiSocketMode mode, T_DjiSocketHandle *socketHandle)
|
||||
{
|
||||
T_SocketHandleStruct *socketHandleStruct;
|
||||
socklen_t optlen = sizeof(int);
|
||||
socklen_t optlen = sizeof (int);
|
||||
int rcvBufSize = SOCKET_RECV_BUF_MAX_SIZE;
|
||||
int opt = 1;
|
||||
|
||||
@ -72,7 +72,8 @@ T_DjiReturnCode Osal_Socket(E_DjiSocketMode mode, T_DjiSocketHandle *socketHandl
|
||||
goto out;
|
||||
}
|
||||
|
||||
if (setsockopt(socketHandleStruct->socketFd, SOL_SOCKET, SO_RCVBUF, &rcvBufSize, optlen) < 0) {
|
||||
if (setsockopt(socketHandleStruct->socketFd, SOL_SOCKET, SO_RCVBUF, &rcvBufSize, optlen) < 0)
|
||||
{
|
||||
goto out;
|
||||
}
|
||||
} else if (mode == DJI_SOCKET_MODE_TCP) {
|
||||
|
@ -81,6 +81,7 @@ static pthread_t s_monitorThread = 0;
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
static T_DjiReturnCode DjiUser_PrepareSystemEnvironment(void);
|
||||
static T_DjiReturnCode DjiUser_CleanSystemEnvironment(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);
|
||||
@ -180,7 +181,8 @@ int main(int argc, char **argv)
|
||||
#endif
|
||||
|
||||
if (aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_EXTENSION_PORT &&
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK) {
|
||||
(aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK)) {
|
||||
returnCode = DjiTest_WidgetInteractionStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("widget interaction sample init error");
|
||||
@ -190,6 +192,13 @@ int main(int argc, char **argv)
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("widget speaker test init error");
|
||||
}
|
||||
|
||||
#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
|
||||
} else {
|
||||
#ifdef CONFIG_MODULE_SAMPLE_CAMERA_EMU_ON
|
||||
returnCode = DjiTest_CameraEmuBaseStartService();
|
||||
@ -339,6 +348,7 @@ static T_DjiReturnCode DjiUser_PrepareSystemEnvironment(void)
|
||||
.Free = Osal_Free,
|
||||
.GetTimeMs = Osal_GetTimeMs,
|
||||
.GetTimeUs = Osal_GetTimeUs,
|
||||
.GetRandomNum = Osal_GetRandomNum,
|
||||
};
|
||||
|
||||
T_DjiLoggerConsole printConsole = {
|
||||
@ -466,6 +476,39 @@ static T_DjiReturnCode DjiUser_PrepareSystemEnvironment(void)
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiUser_CleanSystemEnvironment(void)
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo;
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_POWER_MANAGEMENT_ON
|
||||
returnCode = DjiTest_PowerManagementStopService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
perror("power management deinit error");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_DATA_TRANSMISSION_ON
|
||||
returnCode = DjiTest_DataTransmissionStopService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
perror("widget sample deinit error");
|
||||
}
|
||||
#endif
|
||||
|
||||
returnCode = DjiCore_DeInit();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
perror("Core deinit failed.");
|
||||
}
|
||||
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo)
|
||||
{
|
||||
if (userInfo == NULL) {
|
||||
@ -689,7 +732,15 @@ static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinSta
|
||||
|
||||
static void DjiUser_NormalExitHandler(int signalNum)
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
|
||||
USER_UTIL_UNUSED(signalNum);
|
||||
|
||||
returnCode = DjiUser_CleanSystemEnvironment();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
perror("Clean up system environment failed.");
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
@ -62,17 +62,19 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
ret = libusb_init(NULL);
|
||||
if (ret < 0) {
|
||||
USER_LOG_ERROR("init usb bulk failed, errno = %d", ret);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
handle = libusb_open_device_with_vid_pid(NULL, usbBulkInfo.vid, usbBulkInfo.pid);
|
||||
if (handle == NULL) {
|
||||
USER_LOG_ERROR("open usb device failed");
|
||||
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");
|
||||
USER_LOG_ERROR("libusb claim interface failed, errno = %d", ret);
|
||||
libusb_close(handle);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
@ -114,6 +116,7 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan
|
||||
T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle)
|
||||
{
|
||||
struct libusb_device_handle *handle = NULL;
|
||||
int32_t ret;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
|
||||
if (usbBulkHandle == NULL) {
|
||||
@ -124,7 +127,11 @@ T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle)
|
||||
|
||||
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
libusb_release_interface(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum);
|
||||
ret = libusb_release_interface(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum);
|
||||
if(ret != 0) {
|
||||
USER_LOG_ERROR("release usb bulk interface failed, errno = %d", ret);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
osalHandler->TaskSleepMs(100);
|
||||
libusb_exit(NULL);
|
||||
#endif
|
||||
|
@ -1,5 +1,5 @@
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
project(dji_sdk_demo_on_jeston C)
|
||||
project(dji_sdk_demo_on_jetson C)
|
||||
|
||||
set(CMAKE_C_FLAGS "-pthread -std=gnu99")
|
||||
set(CMAKE_EXE_LINKER_FLAGS "-pthread")
|
@ -337,6 +337,7 @@ static T_DjiReturnCode DjiUser_PrepareSystemEnvironment(void)
|
||||
.SemaphorePost = Osal_SemaphorePost,
|
||||
.Malloc = Osal_Malloc,
|
||||
.Free = Osal_Free,
|
||||
.GetRandomNum = Osal_GetRandomNum,
|
||||
.GetTimeMs = Osal_GetTimeMs,
|
||||
.GetTimeUs = Osal_GetTimeUs,
|
||||
};
|
@ -28,6 +28,7 @@
|
||||
#include "FreeRTOS.h"
|
||||
#include "task.h"
|
||||
#include "semphr.h"
|
||||
#include "stdlib.h"
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define SEM_MUTEX_WAIT_FOREVER 0xFFFFFFFF
|
||||
@ -64,6 +65,10 @@ T_DjiReturnCode Osal_TaskCreate(const char *name, void *(*taskFunc)(void *), uin
|
||||
|
||||
T_DjiReturnCode Osal_TaskDestroy(T_DjiTaskHandle task)
|
||||
{
|
||||
if (task == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
vTaskDelete(task);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
@ -83,6 +88,10 @@ T_DjiReturnCode Osal_TaskSleepMs(uint32_t timeMs)
|
||||
|
||||
T_DjiReturnCode Osal_MutexCreate(T_DjiMutexHandle *mutex)
|
||||
{
|
||||
if (mutex == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
*mutex = xSemaphoreCreateMutex();
|
||||
if (*mutex == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
@ -93,6 +102,10 @@ T_DjiReturnCode Osal_MutexCreate(T_DjiMutexHandle *mutex)
|
||||
|
||||
T_DjiReturnCode Osal_MutexDestroy(T_DjiMutexHandle mutex)
|
||||
{
|
||||
if (mutex == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
vQueueDelete((SemaphoreHandle_t) mutex);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
@ -117,6 +130,10 @@ T_DjiReturnCode Osal_MutexLock(T_DjiMutexHandle mutex)
|
||||
|
||||
T_DjiReturnCode Osal_MutexUnlock(T_DjiMutexHandle mutex)
|
||||
{
|
||||
if (mutex == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
if (xSemaphoreGive(mutex) != pdTRUE) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
}
|
||||
@ -128,6 +145,10 @@ T_DjiReturnCode Osal_SemaphoreCreate(uint32_t initValue, T_DjiSemaHandle *semaph
|
||||
{
|
||||
uint32_t maxCount = UINT_MAX;
|
||||
|
||||
if (semaphore == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
*semaphore = xSemaphoreCreateCounting(maxCount, initValue);
|
||||
|
||||
if (*semaphore == NULL) {
|
||||
@ -139,6 +160,10 @@ T_DjiReturnCode Osal_SemaphoreCreate(uint32_t initValue, T_DjiSemaHandle *semaph
|
||||
|
||||
T_DjiReturnCode Osal_SemaphoreDestroy(T_DjiSemaHandle semaphore)
|
||||
{
|
||||
if (semaphore == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
vSemaphoreDelete(semaphore);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
@ -177,6 +202,10 @@ T_DjiReturnCode Osal_SemaphoreWait(T_DjiSemaHandle semaphore)
|
||||
|
||||
T_DjiReturnCode Osal_SemaphorePost(T_DjiSemaHandle semaphore)
|
||||
{
|
||||
if (semaphore == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
if (xSemaphoreGive(semaphore) != pdTRUE) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
}
|
||||
@ -186,6 +215,10 @@ T_DjiReturnCode Osal_SemaphorePost(T_DjiSemaHandle semaphore)
|
||||
|
||||
T_DjiReturnCode Osal_GetTimeMs(uint32_t *ms)
|
||||
{
|
||||
if (ms == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
*ms = xTaskGetTickCount();
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
@ -193,11 +226,22 @@ T_DjiReturnCode Osal_GetTimeMs(uint32_t *ms)
|
||||
|
||||
T_DjiReturnCode Osal_GetTimeUs(uint64_t *us)
|
||||
{
|
||||
if (us == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
*us = xTaskGetTickCount() * 1000;
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode Osal_GetRandomNum(uint16_t *randomNum)
|
||||
{
|
||||
*randomNum = rand() % 65535;
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
void *Osal_Malloc(uint32_t size)
|
||||
{
|
||||
return pvPortMalloc(size);
|
||||
|
@ -43,35 +43,21 @@ extern "C" {
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
T_DjiReturnCode Osal_TaskCreate(const char *name, void *(*taskFunc)(void *), uint32_t stackSize,
|
||||
void *arg, T_DjiTaskHandle *task);
|
||||
|
||||
T_DjiReturnCode Osal_TaskDestroy(T_DjiTaskHandle task);
|
||||
|
||||
T_DjiReturnCode Osal_TaskSleepMs(uint32_t timeMs);
|
||||
|
||||
T_DjiReturnCode Osal_MutexCreate(T_DjiMutexHandle *mutex);
|
||||
|
||||
T_DjiReturnCode Osal_MutexDestroy(T_DjiMutexHandle mutex);
|
||||
|
||||
T_DjiReturnCode Osal_MutexLock(T_DjiMutexHandle mutex);
|
||||
|
||||
T_DjiReturnCode Osal_MutexUnlock(T_DjiMutexHandle mutex);
|
||||
|
||||
T_DjiReturnCode Osal_SemaphoreCreate(uint32_t initValue, T_DjiSemaHandle *semaphore);
|
||||
|
||||
T_DjiReturnCode Osal_SemaphoreDestroy(T_DjiSemaHandle semaphore);
|
||||
|
||||
T_DjiReturnCode Osal_SemaphoreTimedWait(T_DjiSemaHandle semaphore, uint32_t waitTimeMs);
|
||||
|
||||
T_DjiReturnCode Osal_SemaphoreWait(T_DjiSemaHandle semaphore);
|
||||
|
||||
T_DjiReturnCode Osal_SemaphorePost(T_DjiSemaHandle semaphore);
|
||||
|
||||
T_DjiReturnCode Osal_GetTimeMs(uint32_t *ms);
|
||||
|
||||
T_DjiReturnCode Osal_GetTimeUs(uint64_t *us);
|
||||
|
||||
T_DjiReturnCode Osal_GetRandomNum(uint16_t *randomNum);
|
||||
void *Osal_Malloc(uint32_t size);
|
||||
|
||||
void Osal_Free(void *ptr);
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
@ -97,6 +97,7 @@ void DjiUser_StartTask(void const *argument)
|
||||
.Free = Osal_Free,
|
||||
.GetTimeMs = Osal_GetTimeMs,
|
||||
.GetTimeUs = Osal_GetTimeUs,
|
||||
.GetRandomNum = Osal_GetRandomNum,
|
||||
};
|
||||
T_DjiLoggerConsole printConsole = {
|
||||
.func = DjiUser_PrintConsole,
|
||||
@ -247,7 +248,8 @@ void DjiUser_StartTask(void const *argument)
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON
|
||||
if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK
|
||||
if ((aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK)
|
||||
&& aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) {
|
||||
USER_LOG_WARN("Not support gimbal emu sample.");
|
||||
} else {
|
||||
@ -294,7 +296,8 @@ void DjiUser_StartTask(void const *argument)
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_POSITIONING_ON
|
||||
if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK
|
||||
if ((aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK)
|
||||
&& aircraftInfoBaseInfo.mountPosition != DJI_MOUNT_POSITION_TYPE_EXTENSION_PORT) {
|
||||
if (DjiTest_PositioningStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("psdk positioning init error");
|
||||
|
@ -40,7 +40,7 @@
|
||||
#define UART1_WRITE_BUF_SIZE 64
|
||||
#define UART2_READ_BUF_SIZE 64
|
||||
#define UART2_WRITE_BUF_SIZE 2048
|
||||
#define UART3_READ_BUF_SIZE 4096
|
||||
#define UART3_READ_BUF_SIZE 8192
|
||||
#define UART3_WRITE_BUF_SIZE 2048
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
|
@ -81,11 +81,15 @@ T_DjiReturnCode DjiUpgradePlatformStm32_WriteUpgradeProgramFile(uint32_t offset,
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
__disable_irq();
|
||||
|
||||
result = FLASH_If_Write(APPLICATION_STORE_ADDRESS + offset, (uint8_t *) data, dataLen);
|
||||
if (result != FLASHIF_OK) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
__enable_irq();
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
|
Reference in New Issue
Block a user