NEW: release DJI Payload-SDK version 3.10.0

This commit is contained in:
minghuah.chen
2025-01-10 10:30:38 +08:00
parent 860751ae15
commit 292a6fcb52
104 changed files with 11506 additions and 7194764 deletions

View File

View File

@ -212,27 +212,27 @@ void DjiUser_RunStereoVisionViewSample(void)
switch (inputChar) {
case 'd':
USER_LOG_INFO("Subscribe down stereo camera pair images.");
perceptionSample->SubscribeDownImage(DjiTest_PerceptionImageCallback);
returnCode = perceptionSample->SubscribeDownImage(DjiTest_PerceptionImageCallback);
break;
case 'f':
USER_LOG_INFO("Subscribe front stereo camera pair images.");
perceptionSample->SubscribeFrontImage(DjiTest_PerceptionImageCallback);
returnCode = perceptionSample->SubscribeFrontImage(DjiTest_PerceptionImageCallback);
break;
case 'r':
USER_LOG_INFO("Subscribe rear stereo camera pair images.");
perceptionSample->SubscribeRearImage(DjiTest_PerceptionImageCallback);
returnCode = perceptionSample->SubscribeRearImage(DjiTest_PerceptionImageCallback);
break;
case 'u':
USER_LOG_INFO("Subscribe up stereo camera pair images.");
perceptionSample->SubscribeUpImage(DjiTest_PerceptionImageCallback);
returnCode = perceptionSample->SubscribeUpImage(DjiTest_PerceptionImageCallback);
break;
case 'l':
USER_LOG_INFO("Subscribe left stereo camera pair images.");
perceptionSample->SubscribeLeftImage(DjiTest_PerceptionImageCallback);
returnCode = perceptionSample->SubscribeLeftImage(DjiTest_PerceptionImageCallback);
break;
case 't':
USER_LOG_INFO("Subscribe right stereo camera pair images.");
perceptionSample->SubscribeRightImage(DjiTest_PerceptionImageCallback);
returnCode = perceptionSample->SubscribeRightImage(DjiTest_PerceptionImageCallback);
break;
case 'g':
USER_LOG_INFO("Do stereo camera parameters subscription");
@ -243,6 +243,11 @@ void DjiUser_RunStereoVisionViewSample(void)
break;
}
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_INFO("Failed to subscribe perception image.");
goto DestroyTask;
}
while (true) {
cin >> isQuit;
if (isQuit == 'q' || isQuit == 'Q') {

View File

@ -176,8 +176,6 @@ T_DjiReturnCode Osal_UdpRecvData(T_DjiSocketHandle socketHandle, char *ipAddr, u
ret = recvfrom(socketHandleStruct->socketFd, buf, len, 0, (struct sockaddr *) &addr, &addrLen);
if (ret >= 0) {
*realLen = ret;
strcpy(ipAddr, inet_ntoa(addr.sin_addr));
*port = ntohs(addr.sin_port);
} else {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}

View File

@ -46,7 +46,7 @@ if (DEVICE_SYSTEM_ID MATCHES x86_64)
add_definitions(-DPLATFORM_ARCH_x86_64=1)
elseif (DEVICE_SYSTEM_ID MATCHES aarch64)
set(TOOLCHAIN_NAME aarch64-linux-gnu-gcc)
add_definitions(-DPLATFORM_ARCH_aarch64=1)
add_definitions(-DPLATFORM_ARCH_AARCH64=1)
else ()
message(FATAL_ERROR "FATAL: Please confirm your platform.")
endif ()
@ -133,10 +133,6 @@ 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})

View File

@ -22,8 +22,11 @@ include_directories(../nvidia_jetson/application)
file(GLOB_RECURSE MODULE_SAMPLE_SRC
../../../module_sample/liveview/*.c*
../../../module_sample/camera_manager/*.c*
../../../module_sample/hms_manager/*.c*
../../../module_sample/perception/*.c*
../../../module_sample/gimbal/*.c*
../../../module_sample/flight_controller/*.c*
../../../module_sample/hms_manager/*.c*
../../../../sample_c/module_sample/*.c
)
file(GLOB_RECURSE MODULE_COMMON_SRC ../common/*.c*)
@ -31,7 +34,7 @@ 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(-DPLATFORM_ARCH_AARCH64=1)
add_definitions(-DSYSTEM_ARCH_LINUX=1)
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/../common/3rdparty)
@ -53,7 +56,9 @@ if (OpenCV_FOUND)
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)
# add_definitions(-DOPEN_CV_INSTALLED)
# target_include_directories(${PROJECT_NAME} PRIVATE ${OpenCV_INCLUDE_DIRS})
# target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS})
else ()
message(STATUS "Did not find OpenCV in the system, image data is inside RecvContainer as raw data")
endif ()
@ -78,9 +83,9 @@ if (FFMPEG_FOUND)
message(FATAL_ERROR " - Not support FFMPEG version: ${ffmpeg_major_version}, please install 4.x.x instead.")
endif ()
target_link_libraries(${PROJECT_NAME} ${FFMPEG_LIBRARIES})
include_directories(${FFMPEG_INCLUDE_DIR})
add_definitions(-DFFMPEG_INSTALLED)
# 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)
@ -94,8 +99,8 @@ if (OPUS_FOUND)
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)
# add_definitions(-DOPUS_INSTALLED)
# target_link_libraries(${PROJECT_NAME} /usr/local/lib/libopus.a)
else ()
message(STATUS "Cannot Find OPUS")
endif (OPUS_FOUND)
@ -106,8 +111,8 @@ if (LIBUSB_FOUND)
message(STATUS " - Includes: ${LIBUSB_INCLUDE_DIR}")
message(STATUS " - Libraries: ${LIBUSB_LIBRARY}")
add_definitions(-DLIBUSB_INSTALLED)
target_link_libraries(${PROJECT_NAME} usb-1.0)
# add_definitions(-DLIBUSB_INSTALLED)
# target_link_libraries(${PROJECT_NAME} usb-1.0)
else ()
message(STATUS "Cannot Find LIBUSB")
endif (LIBUSB_FOUND)
@ -118,11 +123,4 @@ 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 ()
add_dependencies(${PROJECT_NAME} djisdk)

View File

@ -35,9 +35,9 @@
#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"
#include "../hal/hal_usb_bulk.h"
#include "../hal/hal_uart.h"
#include "../hal/hal_network.h"
/* Private constants ---------------------------------------------------------*/
#define DJI_LOG_PATH "Logs/DJI"
@ -158,32 +158,34 @@ void Application::DjiUser_SetupEnvironment()
throw std::runtime_error("Register osal handler error.");
}
#if (CONFIG_HARDWARE_CONNECTION == DJI_USE_UART_AND_USB_BULK_DEVICE)
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_RegHalUartHandler(&uartHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Register hal network handler error");
}
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);
returnCode = DjiPlatform_RegHalUartHandler(&uartHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("register osal socket handler error");
throw std::runtime_error("Register hal network handler error");
}
#endif
returnCode = DjiPlatform_RegFileSystemHandler(&fileSystemHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Register osal filesystem handler error.");

View File

@ -40,7 +40,7 @@ extern "C" {
/*!< Attention: Select your hardware connection mode here.
* */
#define CONFIG_HARDWARE_CONNECTION DJI_USE_UART_AND_NETWORK_DEVICE
#define CONFIG_HARDWARE_CONNECTION DJI_USE_ONLY_UART
/* Exported types ------------------------------------------------------------*/

View File

@ -27,10 +27,6 @@
#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>
@ -41,8 +37,13 @@
#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 <flight_controller/test_flight_controller_entry.h>
#include <positioning/test_positioning.h>
#include <hms_manager/hms_manager_entry.h>
#include "camera_manager/test_camera_manager_entry.h"
#include <hms_manager/hms_manager_entry.h>
#include "waypoint_v2/test_waypoint_v2.h"
#include "waypoint_v3/test_waypoint_v3.h"
/* Private constants ---------------------------------------------------------*/
@ -51,8 +52,6 @@
/* 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)
@ -68,25 +67,13 @@ start:
<< "\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"
<< "| [1] Flight controller sample - you can control flying by PSDK |\n"
<< "| [2] Hms info manager sample - get health manger system info by language |\n"
<< "| [a] Gimbal manager sample - you can control gimbal by PSDK |\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"
<< "| [e] Run camera manager sample - you can test camera's functions interactively |\n"
<< "| [f] Start rtk positioning sample - you can receive rtk rtcm data when rtk signal is ok |\n"
<< std::endl;
std::cin >> inputChar;
@ -95,7 +82,7 @@ start:
DjiTest_FcSubscriptionRunSample();
break;
case '1':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_LANDING);
DjiUser_RunFlightControllerSample();
break;
case '2':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_POSITION_CTRL_LANDING);
@ -113,7 +100,7 @@ start:
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SET_GET_PARAM);
break;
case '7':
DjiTest_HmsRunSample();
DjiUser_RunHmsManagerSample();
break;
case '8':
DjiTest_WaypointV2RunSample();
@ -131,77 +118,16 @@ start:
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");
DjiUser_RunCameraManagerSample();
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();
returnCode = DjiTest_PositioningStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("widget sample init error");
USER_LOG_ERROR("rtk positioning 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();
USER_LOG_INFO("Start rtk positioning sample successfully");
break;
default:
break;
@ -213,15 +139,5 @@ start:
}
/* Private functions definition-----------------------------------------------*/
static T_DjiReturnCode DjiTest_HighPowerApplyPinInit()
{
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState)
{
//attention: please pull up the HWPR pin state by hardware.
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/

View File

@ -44,16 +44,27 @@ T_DjiReturnCode HalNetWork_Init(const char *ipAddr, const char *netMask, T_DjiNe
{
int32_t ret;
char cmdStr[LINUX_CMD_STR_MAX_SIZE];
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
int32_t routeIp[4] = {0};
int32_t genMask[4] = {0};
if (ipAddr == NULL || netMask == NULL) {
USER_LOG_ERROR("hal network config param error");
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}
sscanf(ipAddr, "%d.%d.%d.%d", &routeIp[0], &routeIp[1], &routeIp[2], &routeIp[3]);
sscanf(netMask, "%d.%d.%d.%d", &genMask[0], &genMask[1], &genMask[2], &genMask[3]);
routeIp[0] &= genMask[0];
routeIp[1] &= genMask[1];
routeIp[2] &= genMask[2];
routeIp[3] &= genMask[3];
//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);
USER_LOG_DEBUG("%s", cmdStr);
ret = system(cmdStr);
if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Can't open the network."
@ -63,14 +74,34 @@ T_DjiReturnCode HalNetWork_Init(const char *ipAddr, const char *netMask, T_DjiNe
}
snprintf(cmdStr, sizeof(cmdStr), "ifconfig %s %s netmask %s", LINUX_NETWORK_DEV, ipAddr, netMask);
USER_LOG_DEBUG("%s", cmdStr);
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.");
USER_LOG_ERROR("cmd failed: %s", cmdStr);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
osalHandler->TaskSleepMs(50);
snprintf(cmdStr, sizeof(cmdStr), "ip route flush dev %s", LINUX_NETWORK_DEV);
USER_LOG_DEBUG("%s", cmdStr);
ret = system(cmdStr);
if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("cmd failed: %s", cmdStr);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
snprintf(cmdStr, sizeof(cmdStr), "route add -net %d.%d.%d.%d netmask %s dev %s",
routeIp[0], routeIp[1], routeIp[2], routeIp[3], netMask, LINUX_NETWORK_DEV);
USER_LOG_DEBUG("%s", cmdStr);
ret = system(cmdStr);
if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("cmd failed: %s", cmdStr);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
osalHandler->TaskSleepMs(50);
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}

View File

@ -25,6 +25,7 @@
/* Includes ------------------------------------------------------------------*/
#include "hal_usb_bulk.h"
#include "dji_logger.h"
#include <errno.h>
/* Private constants ---------------------------------------------------------*/
#define LINUX_USB_BULK_TRANSFER_TIMEOUT_MS (50)
@ -67,12 +68,13 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan
handle = libusb_open_device_with_vid_pid(NULL, usbBulkInfo.vid, usbBulkInfo.pid);
if (handle == NULL) {
USER_LOG_ERROR("libusb open device error");
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 error");
libusb_close(handle);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
@ -86,22 +88,22 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan
((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);
((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK1_EP_IN_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);
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK1_EP_OUT_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);
((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK2_EP_IN_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);
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK2_EP_OUT_FD, O_RDWR);
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
@ -163,7 +165,13 @@ T_DjiReturnCode HalUsbBulk_WriteData(T_DjiUsbBulkHandle usbBulkHandle, const uin
*realLen = actualLen;
#endif
} else {
*realLen = write(((T_HalUsbBulkObj *) usbBulkHandle)->ep1, buf, len);
ret = write(((T_HalUsbBulkObj *) usbBulkHandle)->ep1, buf, len);
if (ret < 0) {
USER_LOG_ERROR("write ret %d %d %s\n", ret, errno, strerror(errno));
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
} else {
*realLen = ret;
}
}
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
@ -194,7 +202,13 @@ T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *b
*realLen = actualLen;
#endif
} else {
*realLen = read(((T_HalUsbBulkObj *) usbBulkHandle)->ep2, buf, len);
ret = read(((T_HalUsbBulkObj *) usbBulkHandle)->ep2, buf, len);
if (ret < 0) {
USER_LOG_ERROR("read ret %d %d %s\n", ret, errno, strerror(errno));
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
} else {
*realLen = ret;
}
}
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;

View File

@ -52,19 +52,19 @@ 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_EP_IN_FD "/dev/usb-ffs/bulk1/ep1"
#define LINUX_USB_BULK1_EP_OUT_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_BULK1_INTERFACE_NUM (0)
#define LINUX_USB_BULK1_END_POINT_IN (0x81)
#define LINUX_USB_BULK1_END_POINT_OUT (0x01)
#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_EP_IN_FD "/dev/usb-ffs/bulk2/ep1"
#define LINUX_USB_BULK2_EP_OUT_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)
#define LINUX_USB_BULK2_INTERFACE_NUM (1)
#define LINUX_USB_BULK2_END_POINT_IN (0x82)
#define LINUX_USB_BULK2_END_POINT_OUT (0x02)
#ifdef PLATFORM_ARCH_x86_64
#define LINUX_USB_VID (0x0B95)