NEW: release DJI Payload-SDK version 3.2
Signed-off-by: DJI-Martin <DJI-Martin@dji.com>
This commit is contained in:
@ -28,9 +28,7 @@ endif ()
|
|||||||
if (USE_SYSTEM_ARCH MATCHES LINUX)
|
if (USE_SYSTEM_ARCH MATCHES LINUX)
|
||||||
add_definitions(-DSYSTEM_ARCH_LINUX)
|
add_definitions(-DSYSTEM_ARCH_LINUX)
|
||||||
add_subdirectory(samples/sample_c/platform/linux/manifold2)
|
add_subdirectory(samples/sample_c/platform/linux/manifold2)
|
||||||
|
add_subdirectory(samples/sample_c++/platform/linux/manifold2)
|
||||||
message("-- Attention: If you want to use opencv C++ sample, please uncomment the next line.")
|
|
||||||
# add_subdirectory(samples/sample_c++/platform/linux/manifold2)
|
|
||||||
|
|
||||||
execute_process(COMMAND uname -m OUTPUT_VARIABLE DEVICE_SYSTEM_ID)
|
execute_process(COMMAND uname -m OUTPUT_VARIABLE DEVICE_SYSTEM_ID)
|
||||||
if (DEVICE_SYSTEM_ID MATCHES x86_64)
|
if (DEVICE_SYSTEM_ID MATCHES x86_64)
|
||||||
|
76
LICENSE.txt
76
LICENSE.txt
@ -6,11 +6,15 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in
|
|||||||
│ ├── dji_sdk_code_style
|
│ ├── dji_sdk_code_style
|
||||||
│ │ ├── dji_sdk_template.c
|
│ │ ├── dji_sdk_template.c
|
||||||
│ │ └── dji_sdk_template.h
|
│ │ └── dji_sdk_template.h
|
||||||
|
│ ├── reference_designs
|
||||||
|
│ │ └── Type-C Schematic Reference.pdf
|
||||||
│ └── simple_model
|
│ └── simple_model
|
||||||
│ ├── M300_OSDK_Adapter.stp
|
│ ├── M300_OSDK_Adapter.stp
|
||||||
│ ├── M300_RTK_1.stp
|
│ ├── M300_RTK_1.stp
|
||||||
│ ├── M300_RTK_2.stp
|
│ ├── M300_RTK_2.stp
|
||||||
│ ├── M300_RTK_3.stp
|
│ ├── M300_RTK_3.stp
|
||||||
|
│ ├── M30T.stp
|
||||||
|
│ ├── PSDK Mounting Bracket(Payload).stp
|
||||||
│ ├── Skyport_Adapter_2.stp
|
│ ├── Skyport_Adapter_2.stp
|
||||||
│ └── X-Port 80mm.stp
|
│ └── X-Port 80mm.stp
|
||||||
├── EULA.txt
|
├── EULA.txt
|
||||||
@ -43,6 +47,7 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in
|
|||||||
│ │ ├── dji_version.h
|
│ │ ├── dji_version.h
|
||||||
│ │ ├── dji_waypoint_v2.h
|
│ │ ├── dji_waypoint_v2.h
|
||||||
│ │ ├── dji_waypoint_v2_type.h
|
│ │ ├── dji_waypoint_v2_type.h
|
||||||
|
│ │ ├── dji_waypoint_v3.h
|
||||||
│ │ ├── dji_widget.h
|
│ │ ├── dji_widget.h
|
||||||
│ │ ├── dji_xport.h
|
│ │ ├── dji_xport.h
|
||||||
│ │ └── legacy_psdk2.x
|
│ │ └── legacy_psdk2.x
|
||||||
@ -75,7 +80,7 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in
|
|||||||
│ ├── aarch64-linux-gnu-gcc
|
│ ├── aarch64-linux-gnu-gcc
|
||||||
│ │ └── libpayloadsdk.a
|
│ │ └── libpayloadsdk.a
|
||||||
│ ├── armcc_cortex-m4
|
│ ├── armcc_cortex-m4
|
||||||
│ │ └── libpayloadsdk.lib
|
│ │ └── libpayload.lib
|
||||||
│ ├── arm-himix100-linux-gcc
|
│ ├── arm-himix100-linux-gcc
|
||||||
│ │ └── libpayloadsdk.a
|
│ │ └── libpayloadsdk.a
|
||||||
│ ├── arm-himix200-linux-gcc
|
│ ├── arm-himix200-linux-gcc
|
||||||
@ -96,7 +101,9 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in
|
|||||||
│ │ └── libpayloadsdk.a
|
│ │ └── libpayloadsdk.a
|
||||||
│ ├── arm-none-eabi-gcc
|
│ ├── arm-none-eabi-gcc
|
||||||
│ │ └── libpayloadsdk.a
|
│ │ └── libpayloadsdk.a
|
||||||
│ └── x86_64-linux-gnu-gcc
|
│ ├── x86_64-linux-gnu-gcc
|
||||||
|
│ │ └── libpayloadsdk.a
|
||||||
|
│ └── xtensa-esp32-elf-gcc
|
||||||
│ └── libpayloadsdk.a
|
│ └── libpayloadsdk.a
|
||||||
├── README.md
|
├── README.md
|
||||||
├── samples
|
├── samples
|
||||||
@ -186,11 +193,20 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in
|
|||||||
│ │ │ ├── waypoint_v2
|
│ │ │ ├── waypoint_v2
|
||||||
│ │ │ │ ├── test_waypoint_v2.c
|
│ │ │ │ ├── test_waypoint_v2.c
|
||||||
│ │ │ │ └── test_waypoint_v2.h
|
│ │ │ │ └── test_waypoint_v2.h
|
||||||
|
│ │ │ ├── waypoint_v3
|
||||||
|
│ │ │ │ ├── test_waypoint_v3.c
|
||||||
|
│ │ │ │ ├── test_waypoint_v3.h
|
||||||
|
│ │ │ │ ├── waypoint_file
|
||||||
|
│ │ │ │ │ └── waypoint_v3_test_file.kmz
|
||||||
|
│ │ │ │ └── waypoint_file_c
|
||||||
|
│ │ │ │ └── waypoint_v3_test_file_kmz.h
|
||||||
│ │ │ ├── widget
|
│ │ │ ├── widget
|
||||||
│ │ │ │ ├── file_binary_array_list_en.c
|
│ │ │ │ ├── file_binary_array_list_en.c
|
||||||
│ │ │ │ ├── file_binary_array_list_en.h
|
│ │ │ │ ├── file_binary_array_list_en.h
|
||||||
│ │ │ │ ├── test_widget.c
|
│ │ │ │ ├── test_widget.c
|
||||||
│ │ │ │ ├── test_widget.h
|
│ │ │ │ ├── test_widget.h
|
||||||
|
│ │ │ │ ├── test_widget_speaker.c
|
||||||
|
│ │ │ │ ├── test_widget_speaker.h
|
||||||
│ │ │ │ ├── widget_file
|
│ │ │ │ ├── widget_file
|
||||||
│ │ │ │ │ ├── cn_big_screen
|
│ │ │ │ │ ├── cn_big_screen
|
||||||
│ │ │ │ │ │ ├── icon_button1.png
|
│ │ │ │ │ │ ├── icon_button1.png
|
||||||
@ -261,8 +277,9 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in
|
|||||||
│ │ ├── linux
|
│ │ ├── linux
|
||||||
│ │ │ ├── common
|
│ │ │ ├── common
|
||||||
│ │ │ │ ├── 3rdparty
|
│ │ │ │ ├── 3rdparty
|
||||||
│ │ │ │ │ └── ffmpeg
|
│ │ │ │ │ ├── FindFFMPEG.cmake
|
||||||
│ │ │ │ │ └── FindFFMPEG.cmake
|
│ │ │ │ │ ├── FindLIBUSB.cmake
|
||||||
|
│ │ │ │ │ └── FindOPUS.cmake
|
||||||
│ │ │ │ ├── monitor
|
│ │ │ │ ├── monitor
|
||||||
│ │ │ │ │ ├── sys_monitor.c
|
│ │ │ │ │ ├── sys_monitor.c
|
||||||
│ │ │ │ │ └── sys_monitor.h
|
│ │ │ │ │ └── sys_monitor.h
|
||||||
@ -302,12 +319,24 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in
|
|||||||
│ │ │ ├── dji_sdk_config.h
|
│ │ │ ├── dji_sdk_config.h
|
||||||
│ │ │ ├── FreeRTOSConfig.h
|
│ │ │ ├── FreeRTOSConfig.h
|
||||||
│ │ │ └── main.c
|
│ │ │ └── main.c
|
||||||
|
│ │ ├── bootloader
|
||||||
|
│ │ │ ├── common.c
|
||||||
|
│ │ │ ├── common.h
|
||||||
|
│ │ │ ├── main.c
|
||||||
|
│ │ │ ├── main.h
|
||||||
|
│ │ │ ├── menu.c
|
||||||
|
│ │ │ ├── menu.h
|
||||||
|
│ │ │ └── ymodem.c
|
||||||
│ │ ├── drivers
|
│ │ ├── drivers
|
||||||
│ │ │ ├── BSP
|
│ │ │ ├── BSP
|
||||||
│ │ │ │ ├── apply_high_power.c
|
│ │ │ │ ├── apply_high_power.c
|
||||||
│ │ │ │ ├── apply_high_power.h
|
│ │ │ │ ├── apply_high_power.h
|
||||||
|
│ │ │ │ ├── button.c
|
||||||
|
│ │ │ │ ├── button.h
|
||||||
│ │ │ │ ├── dji_ringbuffer.c
|
│ │ │ │ ├── dji_ringbuffer.c
|
||||||
│ │ │ │ ├── dji_ringbuffer.h
|
│ │ │ │ ├── dji_ringbuffer.h
|
||||||
|
│ │ │ │ ├── flash_if.c
|
||||||
|
│ │ │ │ ├── flash_if.h
|
||||||
│ │ │ │ ├── freertos.c
|
│ │ │ │ ├── freertos.c
|
||||||
│ │ │ │ ├── led.c
|
│ │ │ │ ├── led.c
|
||||||
│ │ │ │ ├── led.h
|
│ │ │ │ ├── led.h
|
||||||
@ -321,15 +350,16 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in
|
|||||||
│ │ │ │ ├── stm32f4xx_it.h
|
│ │ │ │ ├── stm32f4xx_it.h
|
||||||
│ │ │ │ ├── syscalls.c
|
│ │ │ │ ├── syscalls.c
|
||||||
│ │ │ │ ├── sysmem.c
|
│ │ │ │ ├── sysmem.c
|
||||||
|
│ │ │ │ ├── sysmem.h
|
||||||
│ │ │ │ ├── system_stm32f4xx.c
|
│ │ │ │ ├── system_stm32f4xx.c
|
||||||
│ │ │ │ ├── uart.c
|
│ │ │ │ ├── uart.c
|
||||||
│ │ │ │ └── uart.h
|
│ │ │ │ ├── uart.h
|
||||||
|
│ │ │ │ ├── upgrade_platform_opt_stm32.c
|
||||||
|
│ │ │ │ └── upgrade_platform_opt_stm32.h
|
||||||
│ │ │ ├── CMSIS
|
│ │ │ ├── CMSIS
|
||||||
│ │ │ │ ├── Device
|
│ │ │ │ ├── Device
|
||||||
│ │ │ │ │ └── ST
|
│ │ │ │ │ └── ST
|
||||||
│ │ │ │ │ └── STM32F4xx
|
│ │ │ │ │ └── STM32F4xx
|
||||||
│ │ │ │ │ ├── Include
|
|
||||||
│ │ │ │ │ └── Source
|
|
||||||
│ │ │ │ └── Include
|
│ │ │ │ └── Include
|
||||||
│ │ │ ├── STM32F4xx_HAL_Driver
|
│ │ │ ├── STM32F4xx_HAL_Driver
|
||||||
│ │ │ │ ├── Inc
|
│ │ │ │ ├── Inc
|
||||||
@ -378,21 +408,22 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in
|
|||||||
│ │ │ ├── stream_buffer.c
|
│ │ │ ├── stream_buffer.c
|
||||||
│ │ │ ├── tasks.c
|
│ │ │ ├── tasks.c
|
||||||
│ │ │ └── timers.c
|
│ │ │ └── timers.c
|
||||||
│ │ └── project
|
│ │ ├── project
|
||||||
│ │ ├── clion_app
|
│ │ │ ├── armgcc
|
||||||
│ │ │ ├── CMakeLists.txt
|
│ │ │ │ ├── CMakeLists.txt
|
||||||
│ │ │ ├── STM32F407VGTX_FLASH.ld
|
│ │ │ │ ├── STM32F407VGTX_FLASH.ld
|
||||||
│ │ │ └── stm32f4discovery.cfg
|
│ │ │ │ └── stm32f4discovery.cfg
|
||||||
│ │ └── mdk_app
|
│ │ │ ├── mdk
|
||||||
│ │ └── mdk_app.uvprojx
|
│ │ │ │ └── mdk_app.uvprojx
|
||||||
|
│ │ │ └── mdk_bootloader
|
||||||
|
│ │ │ └── mdk_bootloader.uvprojx
|
||||||
|
│ │ └── readme.txt
|
||||||
│ └── sample_c++
|
│ └── sample_c++
|
||||||
│ ├── module_sample
|
│ ├── module_sample
|
||||||
│ │ ├── liveview
|
│ │ ├── liveview
|
||||||
│ │ │ ├── data
|
│ │ │ ├── data
|
||||||
│ │ │ │ ├── cars.xml
|
|
||||||
│ │ │ │ ├── haarcascade_frontalface_alt.xml
|
│ │ │ │ ├── haarcascade_frontalface_alt.xml
|
||||||
│ │ │ │ └── tensorflow
|
│ │ │ │ └── tensorflow
|
||||||
│ │ │ │ ├── frozen_inference_graph.pb
|
|
||||||
│ │ │ │ └── ssd_inception_v2_coco_2017_11_17.pbtxt
|
│ │ │ │ └── ssd_inception_v2_coco_2017_11_17.pbtxt
|
||||||
│ │ │ ├── dji_camera_image_handler.cpp
|
│ │ │ ├── dji_camera_image_handler.cpp
|
||||||
│ │ │ ├── dji_camera_image_handler.hpp
|
│ │ │ ├── dji_camera_image_handler.hpp
|
||||||
@ -410,9 +441,17 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in
|
|||||||
│ └── platform
|
│ └── platform
|
||||||
│ └── linux
|
│ └── linux
|
||||||
│ ├── common
|
│ ├── common
|
||||||
|
│ │ ├── 3rdparty
|
||||||
|
│ │ │ ├── FindFFMPEG.cmake
|
||||||
|
│ │ │ ├── FindLIBUSB.cmake
|
||||||
|
│ │ │ └── FindOPUS.cmake
|
||||||
│ │ └── osal
|
│ │ └── osal
|
||||||
│ │ ├── osal.c
|
│ │ ├── osal.c
|
||||||
│ │ └── osal.h
|
│ │ ├── osal_fs.c
|
||||||
|
│ │ ├── osal_fs.h
|
||||||
|
│ │ ├── osal.h
|
||||||
|
│ │ ├── osal_socket.c
|
||||||
|
│ │ └── osal_socket.h
|
||||||
│ └── manifold2
|
│ └── manifold2
|
||||||
│ ├── application
|
│ ├── application
|
||||||
│ │ ├── application.cpp
|
│ │ ├── application.cpp
|
||||||
@ -420,14 +459,13 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in
|
|||||||
│ │ ├── dji_sdk_app_info.h
|
│ │ ├── dji_sdk_app_info.h
|
||||||
│ │ └── main.cpp
|
│ │ └── main.cpp
|
||||||
│ ├── CMakeLists.txt
|
│ ├── CMakeLists.txt
|
||||||
│ ├── FindFFMPEG.cmake
|
|
||||||
│ └── hal
|
│ └── hal
|
||||||
│ ├── hal_network.c
|
│ ├── hal_network.c
|
||||||
│ ├── hal_network.h
|
│ ├── hal_network.h
|
||||||
│ ├── hal_uart.c
|
│ ├── hal_uart.c
|
||||||
│ ├── hal_uart.h
|
│ ├── hal_uart.h
|
||||||
│ ├── hal_usb_bulk.c
|
│ ├── hal_usb_bulk.c
|
||||||
│ └── hal_usb_bulk.h
|
│ └── hal_usb_bulk.h
|
||||||
└── tools
|
└── tools
|
||||||
└── file2c
|
└── file2c
|
||||||
├── file2c.exe
|
├── file2c.exe
|
||||||
|
32
README.md
32
README.md
@ -1,6 +1,6 @@
|
|||||||
# DJI Payload SDK (PSDK)
|
# DJI Payload SDK (PSDK)
|
||||||
|
|
||||||

|

|
||||||

|

|
||||||

|

|
||||||
[](https://gitter.im/dji-sdk/Payload-SDK?utm_source=badge&utm_medium=badge&utm_campaign=pr-badge&utm_content=badge)
|
[](https://gitter.im/dji-sdk/Payload-SDK?utm_source=badge&utm_medium=badge&utm_campaign=pr-badge&utm_content=badge)
|
||||||
@ -15,17 +15,31 @@ Payload Controller, Video Image Analysis Platform, Mapping Camera, Megaphone And
|
|||||||
|
|
||||||
## Documentation
|
## Documentation
|
||||||
|
|
||||||
For full documentation, please visit the [DJI Developer Documentation](https://developer.dji.com/payload-sdk/documentation/).
|
For full documentation, please visit
|
||||||
Documentation regarding the code can be found in the [PSDK API Reference](https://developer.dji.com/payload-api-reference/introduction/index.html) section of the developer's website.
|
the [DJI Developer Documentation](https://developer.dji.com/payload-sdk/documentation/). Documentation regarding the
|
||||||
Please visit the [Latest Version Information](https://developer.dji.com/payload-sdk/documentation/appendix/firmware.html) to get the latest version information.
|
code can be found in the [PSDK API Reference](https://developer.dji.com/payload-api-reference/introduction/index.html)
|
||||||
|
section of the developer's website. Please visit
|
||||||
|
the [Latest Version Information](https://developer.dji.com/payload-sdk/documentation/appendix/firmware.html) to get the
|
||||||
|
latest version information.
|
||||||
|
|
||||||
## Latest Release
|
## Latest Release
|
||||||
|
|
||||||
PSDK 3.1.0 was released on 21 March 2022. This version of Payload SDK mainly add some features support, such as add the
|
PSDK 3.2.0 was released on 08 August 2022. This version of Payload SDK mainly add some features support and fixed some
|
||||||
Matrice 30/30T support, add the standard speaker widget support on M30/M30T, add the waypoint 3.0 support on M30/30T, add the
|
bugs. Please refer to the release notes for detailed changes list.
|
||||||
get camera laser ranging data support on M30/30T, add the power-off notification support on M300 RTK OSDK port, etc. At
|
|
||||||
the same time, we also fixed some bugs on the last version, add more sample support and add ESP32 toolchain support.
|
* Add the support of standard speaker on M300 RTK, M30/M30T Pilot
|
||||||
Please refer to the release notes for detailed changes list.
|
* Add the support of the mapping between the speaker with the remote controller button on M300 RTK, M30/M30T Pilot
|
||||||
|
* Add function support for H20N on M300 RTK
|
||||||
|
* Add infrared zoom function support of H20T on M300 RTK
|
||||||
|
* Fix the occasional problem of the Camera Livestream can not be subscribed on M30/M30T
|
||||||
|
* Fix the problem of some interfaces of camera management run error on M30/M30T
|
||||||
|
* Fix the problem of the infrared code stream can not be obtained on M30/M30T
|
||||||
|
* Fix the problem of RTOS platform data subscription crash on M30/M30T
|
||||||
|
* Fix the occasional problem of abnormal media download function on M300 RTK
|
||||||
|
* Fix the occasional problem of abnormal SDK interconnection function on M300 RTK
|
||||||
|
* Fix the occasional problem of the PSDK payload name displays abnormally
|
||||||
|
* Fix the coordinate system problem of the gimbal angle of the data subscription function
|
||||||
|
* Optimize the compilation dependency problems of third-party dependent libraries
|
||||||
|
|
||||||
## License
|
## License
|
||||||
|
|
||||||
|
@ -509,7 +509,8 @@ typedef enum {
|
|||||||
typedef struct {
|
typedef struct {
|
||||||
E_DjiDownloadFileEvent downloadFileEvent;
|
E_DjiDownloadFileEvent downloadFileEvent;
|
||||||
uint32_t fileIndex;
|
uint32_t fileIndex;
|
||||||
uint8_t progressInPercent;
|
uint32_t fileSize;
|
||||||
|
float progressInPercent;
|
||||||
} T_DjiDownloadFilePacketInfo;
|
} T_DjiDownloadFilePacketInfo;
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
@ -767,6 +768,15 @@ T_DjiReturnCode DjiCameraManager_SetOpticalZoomParam(E_DjiMountPosition position
|
|||||||
T_DjiReturnCode DjiCameraManager_GetOpticalZoomParam(E_DjiMountPosition position,
|
T_DjiReturnCode DjiCameraManager_GetOpticalZoomParam(E_DjiMountPosition position,
|
||||||
T_DjiCameraManagerOpticalZoomParam *opticalZoomParam);
|
T_DjiCameraManagerOpticalZoomParam *opticalZoomParam);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Set parameters for camera infrared zooming of the selected camera mounted position.
|
||||||
|
* @param position: camera mounted position
|
||||||
|
* @param factor: target zoom factor.
|
||||||
|
* @return Execution result.
|
||||||
|
*/
|
||||||
|
T_DjiReturnCode DjiCameraManager_SetInfraredZoomParam(E_DjiMountPosition position,
|
||||||
|
dji_f32_t factor);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Stop camera optical zooming of the selected camera mounted position.
|
* @brief Stop camera optical zooming of the selected camera mounted position.
|
||||||
* @note Called to stop focal length changing, when it currently is from
|
* @note Called to stop focal length changing, when it currently is from
|
||||||
@ -957,6 +967,8 @@ T_DjiReturnCode DjiCameraManager_StopRecordVideo(E_DjiMountPosition position);
|
|||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Download selected camera media file list.
|
* @brief Download selected camera media file list.
|
||||||
|
* @note The interface is a synchronous interface, which occupies more CPU resources when using it.
|
||||||
|
* If the download file fails, the timeout time is 3S.
|
||||||
* @param position: the mount position of the camera
|
* @param position: the mount position of the camera
|
||||||
* @param fileList: the pointer to the downloaded camera file list
|
* @param fileList: the pointer to the downloaded camera file list
|
||||||
* @return Execution result.
|
* @return Execution result.
|
||||||
@ -975,7 +987,8 @@ T_DjiReturnCode DjiCameraManager_RegDownloadFileDataCallback(E_DjiMountPosition
|
|||||||
/**
|
/**
|
||||||
* @brief Download selected camera media file by file index.
|
* @brief Download selected camera media file by file index.
|
||||||
* @note Only support download one file at the same time, the new file download need wait for the previous file
|
* @note Only support download one file at the same time, the new file download need wait for the previous file
|
||||||
* download finished.
|
* download finished.The interface is a synchronous interface, which occupies more CPU resources when using it.
|
||||||
|
* If the download file fails, the timeout time is 3S.
|
||||||
* @param position: the mount position of the camera
|
* @param position: the mount position of the camera
|
||||||
* @param fileIndex: the index of the camera media file
|
* @param fileIndex: the index of the camera media file
|
||||||
* @return Execution result.
|
* @return Execution result.
|
||||||
|
@ -89,6 +89,12 @@ T_DjiReturnCode DjiCore_SetAlias(const char *productAlias);
|
|||||||
*/
|
*/
|
||||||
T_DjiReturnCode DjiCore_ApplicationStart(void);
|
T_DjiReturnCode DjiCore_ApplicationStart(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief DeInitialize the Payload SDK core in blocking mode.
|
||||||
|
* @return Execution result.
|
||||||
|
*/
|
||||||
|
T_DjiReturnCode DjiCore_DeInit(void);
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -157,7 +157,6 @@ typedef enum {
|
|||||||
*
|
*
|
||||||
* @note This value is updated each time the drone takes off.
|
* @note This value is updated each time the drone takes off.
|
||||||
*
|
*
|
||||||
* @sensors Visual Odometry (M210 only), Barometer, IMU
|
|
||||||
* @units m
|
* @units m
|
||||||
* @datastruct \ref T_DjiFcSubscriptionAltitudeOfHomePoint
|
* @datastruct \ref T_DjiFcSubscriptionAltitudeOfHomePoint
|
||||||
*/
|
*/
|
||||||
@ -935,8 +934,7 @@ typedef struct BatterySingleInfo {
|
|||||||
*/
|
*/
|
||||||
typedef struct SDKCtrlInfo {
|
typedef struct SDKCtrlInfo {
|
||||||
uint8_t controlMode; /*!< See CtlrMode in dji_status.hpp*/
|
uint8_t controlMode; /*!< See CtlrMode in dji_status.hpp*/
|
||||||
uint8_t deviceStatus: 3; /*!< For M300 and M210V2(firmware version V01.00.0690 and later):0->rc 1->app 4->serial;
|
uint8_t deviceStatus: 3; /*!< 0->rc 1->app 4->serial */
|
||||||
Other: 0->rc 1->app 2->serial*/
|
|
||||||
uint8_t flightStatus: 1; /*!< 1->opensd 0->close */
|
uint8_t flightStatus: 1; /*!< 1->opensd 0->close */
|
||||||
uint8_t vrcStatus: 1;
|
uint8_t vrcStatus: 1;
|
||||||
uint8_t reserved: 3;
|
uint8_t reserved: 3;
|
||||||
@ -1062,7 +1060,6 @@ typedef struct PositionVO {
|
|||||||
/*!
|
/*!
|
||||||
* @brief struct for data broadcast and subscription, return obstacle info around the vehicle
|
* @brief struct for data broadcast and subscription, return obstacle info around the vehicle
|
||||||
*
|
*
|
||||||
* @note available in M210 (front, up, down)
|
|
||||||
*/
|
*/
|
||||||
typedef struct RelativePosition {
|
typedef struct RelativePosition {
|
||||||
dji_f32_t down; /*!< distance from obstacle (m) */
|
dji_f32_t down; /*!< distance from obstacle (m) */
|
||||||
@ -1170,7 +1167,8 @@ T_DjiReturnCode DjiFcSubscription_SubscribeTopic(E_DjiFcSubscriptionTopic topic,
|
|||||||
* @param timestamp: pointer to memory space used to store timestamps. The memory space used to store timestamps
|
* @param timestamp: pointer to memory space used to store timestamps. The memory space used to store timestamps
|
||||||
* have to have been allocated correctly, and should ensure its size is equal to data structure size of timestamp,
|
* have to have been allocated correctly, and should ensure its size is equal to data structure size of timestamp,
|
||||||
* otherwise, this function will not be able to return data and timestamp (return error code) or even cause memory
|
* otherwise, this function will not be able to return data and timestamp (return error code) or even cause memory
|
||||||
* overflow event. If the user does not need timestamp information, can fill in NULL.
|
* overflow event. If the user does not need timestamp information, can fill in NULL. Use flight controller power-on
|
||||||
|
* timestamp on M300 RTK. Use payload local timestamp on M30/M30T.
|
||||||
* @return Execution result.
|
* @return Execution result.
|
||||||
*/
|
*/
|
||||||
T_DjiReturnCode DjiFcSubscription_GetLatestValueOfTopic(E_DjiFcSubscriptionTopic topic,
|
T_DjiReturnCode DjiFcSubscription_GetLatestValueOfTopic(E_DjiFcSubscriptionTopic topic,
|
||||||
|
@ -294,7 +294,7 @@ DjiFlightController_GetRtkPositionEnableStatus(E_DjiFlightControllerRtkPositionE
|
|||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Set rc lost action.
|
* @brief Set rc lost action.
|
||||||
* @note It will be valid when rc and osdk is both lost.It only support M320.
|
* @note It will be valid when rc and osdk is both lost.It only support M30.
|
||||||
* @param rcLostAction: actions when rc is lost.(hover/landing/go home).It keeps in sync with pilot's param.
|
* @param rcLostAction: actions when rc is lost.(hover/landing/go home).It keeps in sync with pilot's param.
|
||||||
* @return Execution result.
|
* @return Execution result.
|
||||||
*/
|
*/
|
||||||
@ -302,7 +302,7 @@ T_DjiReturnCode DjiFlightController_SetRCLostAction(E_DjiFlightControllerRCLostA
|
|||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Get rc lost action(hover/landing/gohome).
|
* @brief Get rc lost action(hover/landing/gohome).
|
||||||
* @note It will be valid when rc and osdk is both lost.It only support M320.
|
* @note It will be valid when rc and osdk is both lost.It only support M30.
|
||||||
* @param rcLostAction: see reference of E_DjiFlightControllerRCLostAction.It keeps in sync with pilot's param.
|
* @param rcLostAction: see reference of E_DjiFlightControllerRCLostAction.It keeps in sync with pilot's param.
|
||||||
* @return Execution result.
|
* @return Execution result.
|
||||||
*/
|
*/
|
||||||
@ -583,7 +583,7 @@ T_DjiReturnCode DjiFlightController_ExecuteEmergencyBrakeAction(void);
|
|||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Request cancel emergency brake action.
|
* @brief Request cancel emergency brake action.
|
||||||
* @note It is only support on M320.If you use DjiFlightController_ExecuteEmergencyBrakeAction(), you need to use
|
* @note It is only support on M30.If you use DjiFlightController_ExecuteEmergencyBrakeAction(), you need to use
|
||||||
* "DjiFlightController_CancelEmergencyBrakeAction()" to allow aircraft to execute drone action again.
|
* "DjiFlightController_CancelEmergencyBrakeAction()" to allow aircraft to execute drone action again.
|
||||||
* @return Execution result.
|
* @return Execution result.
|
||||||
*/
|
*/
|
||||||
|
@ -114,6 +114,7 @@ typedef enum {
|
|||||||
DJI_CAMERA_TYPE_XTS = 41, /*!< Camera type is XT S. */
|
DJI_CAMERA_TYPE_XTS = 41, /*!< Camera type is XT S. */
|
||||||
DJI_CAMERA_TYPE_H20 = 42, /*!< Camera type is H20. */
|
DJI_CAMERA_TYPE_H20 = 42, /*!< Camera type is H20. */
|
||||||
DJI_CAMERA_TYPE_H20T = 43, /*!< Camera type is H20T. */
|
DJI_CAMERA_TYPE_H20T = 43, /*!< Camera type is H20T. */
|
||||||
|
DJI_CAMERA_TYPE_H20N = 61, /*!< Camera type is H20N. */
|
||||||
DJI_CAMERA_TYPE_P1 = 50, /*!< Camera type is P1. */
|
DJI_CAMERA_TYPE_P1 = 50, /*!< Camera type is P1. */
|
||||||
DJI_CAMERA_TYPE_L1, /*!< Camera type is L1. */
|
DJI_CAMERA_TYPE_L1, /*!< Camera type is L1. */
|
||||||
DJI_CAMERA_TYPE_M30, /*!< Camera type is M30. */
|
DJI_CAMERA_TYPE_M30, /*!< Camera type is M30. */
|
||||||
@ -256,7 +257,7 @@ typedef enum {
|
|||||||
typedef enum {
|
typedef enum {
|
||||||
/*! The number of pictures to continuously take each time in BURST mode is 2
|
/*! The number of pictures to continuously take each time in BURST mode is 2
|
||||||
*/
|
*/
|
||||||
DJI_CAMERA_BURST_COUNT_2 = 2,
|
DJI_CAMERA_BURST_COUNT_2 = 2,
|
||||||
/*! The number of pictures to continuously take each time in BURST mode is 3
|
/*! The number of pictures to continuously take each time in BURST mode is 3
|
||||||
*/
|
*/
|
||||||
DJI_CAMERA_BURST_COUNT_3 = 3,
|
DJI_CAMERA_BURST_COUNT_3 = 3,
|
||||||
@ -359,7 +360,8 @@ typedef struct {
|
|||||||
* @param data: pointer to data of the topic, user need transfer type of this pointer to the corresponding data structure
|
* @param data: pointer to data of the topic, user need transfer type of this pointer to the corresponding data structure
|
||||||
* pointer for getting every item of the topic conveniently.
|
* pointer for getting every item of the topic conveniently.
|
||||||
* @param dataSize: the size of memory space pointed by data argument, equal to data structure size corresponding to the topic.
|
* @param dataSize: the size of memory space pointed by data argument, equal to data structure size corresponding to the topic.
|
||||||
* @param timestamp: pointer to timestamp corresponding this data.
|
* @param timestamp: pointer to timestamp corresponding this data. Use flight controller power-on timestamp on M300 RTK.
|
||||||
|
* Use payload local timestamp on M30/M30T.
|
||||||
* @return Execution result.
|
* @return Execution result.
|
||||||
*/
|
*/
|
||||||
typedef T_DjiReturnCode (*DjiReceiveDataOfTopicCallback)(const uint8_t *data, uint16_t dataSize,
|
typedef T_DjiReturnCode (*DjiReceiveDataOfTopicCallback)(const uint8_t *data, uint16_t dataSize,
|
||||||
|
@ -34,10 +34,10 @@ extern "C" {
|
|||||||
|
|
||||||
/* Exported constants --------------------------------------------------------*/
|
/* Exported constants --------------------------------------------------------*/
|
||||||
#define DJI_VERSION_MAJOR 3 /*!< DJI SDK major version num, when have incompatible API changes. Range from 0 to 99. */
|
#define DJI_VERSION_MAJOR 3 /*!< DJI SDK major version num, when have incompatible API changes. Range from 0 to 99. */
|
||||||
#define DJI_VERSION_MINOR 1 /*!< DJI SDK minor version num, when add functionality in a backwards compatible manner changes. Range from 0 to 99. */
|
#define DJI_VERSION_MINOR 2 /*!< DJI SDK minor version num, when add functionality in a backwards compatible manner changes. Range from 0 to 99. */
|
||||||
#define DJI_VERSION_MODIFY 0 /*!< DJI SDK modify version num, when have backwards compatible bug fixes changes. Range from 0 to 99. */
|
#define DJI_VERSION_MODIFY 0 /*!< DJI SDK modify version num, when have backwards compatible bug fixes changes. Range from 0 to 99. */
|
||||||
#define DJI_VERSION_BETA 0 /*!< DJI SDK version beta info, release version will be 0, when beta version release changes. Range from 0 to 255. */
|
#define DJI_VERSION_BETA 0 /*!< DJI SDK version beta info, release version will be 0, when beta version release changes. Range from 0 to 255. */
|
||||||
#define DJI_VERSION_BUILD 1509 /*!< DJI SDK version build info, when jenkins trigger build changes. Range from 0 to 65535. */
|
#define DJI_VERSION_BUILD 1539 /*!< DJI SDK version build info, when jenkins trigger build changes. Range from 0 to 65535. */
|
||||||
|
|
||||||
/* Exported types ------------------------------------------------------------*/
|
/* Exported types ------------------------------------------------------------*/
|
||||||
|
|
||||||
|
@ -191,13 +191,9 @@ typedef struct {
|
|||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
T_DjiReturnCode (*GetSpeakerState)(T_DjiWidgetSpeakerState *speakerState);
|
T_DjiReturnCode (*GetSpeakerState)(T_DjiWidgetSpeakerState *speakerState);
|
||||||
|
|
||||||
T_DjiReturnCode (*SetWorkMode)(E_DjiWidgetSpeakerWorkMode workMode);
|
T_DjiReturnCode (*SetWorkMode)(E_DjiWidgetSpeakerWorkMode workMode);
|
||||||
T_DjiReturnCode (*GetWorkMode)(E_DjiWidgetSpeakerWorkMode *workMode);
|
|
||||||
T_DjiReturnCode (*SetPlayMode)(E_DjiWidgetSpeakerPlayMode playMode);
|
T_DjiReturnCode (*SetPlayMode)(E_DjiWidgetSpeakerPlayMode playMode);
|
||||||
T_DjiReturnCode (*GetPlayMode)(E_DjiWidgetSpeakerPlayMode *playMode);
|
|
||||||
T_DjiReturnCode (*SetVolume)(uint8_t volume);
|
T_DjiReturnCode (*SetVolume)(uint8_t volume);
|
||||||
T_DjiReturnCode (*GetVolume)(uint8_t *volume);
|
|
||||||
|
|
||||||
T_DjiReturnCode (*StartPlay)(void);
|
T_DjiReturnCode (*StartPlay)(void);
|
||||||
T_DjiReturnCode (*StopPlay)(void);
|
T_DjiReturnCode (*StopPlay)(void);
|
||||||
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
34
samples/sample_c++/platform/linux/common/3rdparty/FindLIBUSB.cmake
vendored
Normal file
34
samples/sample_c++/platform/linux/common/3rdparty/FindLIBUSB.cmake
vendored
Normal file
@ -0,0 +1,34 @@
|
|||||||
|
#
|
||||||
|
# Find the native LIBUSB includes and library
|
||||||
|
#
|
||||||
|
# This module defines
|
||||||
|
# LIBUSB_INCLUDE_DIR, where to find libusb.h
|
||||||
|
# LIBUSB_LIBRARY, the libraries to link against to use LIBUSB.
|
||||||
|
# LIBUSB_FOUND, If false, do not try to use LIBUSB.
|
||||||
|
|
||||||
|
FIND_PATH(LIBUSB_INCLUDE_DIR libusb.h
|
||||||
|
PATHS
|
||||||
|
/usr/local/include/libusb-1.0
|
||||||
|
/usr/include/libusb-1.0
|
||||||
|
/opt/local/include
|
||||||
|
/opt/include
|
||||||
|
)
|
||||||
|
|
||||||
|
get_filename_component(LIBUSB_INCLUDE_DIR ${LIBUSB_INCLUDE_DIR} ABSOLUTE)
|
||||||
|
|
||||||
|
FIND_LIBRARY(LIBUSB_LIBRARY usb-1.0
|
||||||
|
/usr/local/lib
|
||||||
|
/usr/lib
|
||||||
|
)
|
||||||
|
|
||||||
|
IF (LIBUSB_INCLUDE_DIR)
|
||||||
|
IF (LIBUSB_LIBRARY)
|
||||||
|
SET(LIBUSB_FOUND "YES")
|
||||||
|
ENDIF (LIBUSB_LIBRARY)
|
||||||
|
ENDIF (LIBUSB_INCLUDE_DIR)
|
||||||
|
|
||||||
|
MARK_AS_ADVANCED(
|
||||||
|
LIBUSB_INCLUDE_DIR
|
||||||
|
LIBUSB_LIBRARY
|
||||||
|
LIBUSB_FOUND
|
||||||
|
)
|
34
samples/sample_c++/platform/linux/common/3rdparty/FindOPUS.cmake
vendored
Normal file
34
samples/sample_c++/platform/linux/common/3rdparty/FindOPUS.cmake
vendored
Normal file
@ -0,0 +1,34 @@
|
|||||||
|
#
|
||||||
|
# Find the native OPUS includes and library
|
||||||
|
#
|
||||||
|
# This module defines
|
||||||
|
# OPUS_INCLUDE_DIR, where to find opus.h
|
||||||
|
# OPUS_LIBRARY, the libraries to link against to use OPUS.
|
||||||
|
# OPUS_FOUND, If false, do not try to use OPUS.
|
||||||
|
|
||||||
|
FIND_PATH(OPUS_INCLUDE_DIR opus.h
|
||||||
|
PATHS
|
||||||
|
/usr/local/include/opus
|
||||||
|
/usr/include/opus
|
||||||
|
/opt/local/include
|
||||||
|
/opt/include
|
||||||
|
)
|
||||||
|
|
||||||
|
get_filename_component(OPUS_INCLUDE_DIR ${OPUS_INCLUDE_DIR} ABSOLUTE)
|
||||||
|
|
||||||
|
FIND_LIBRARY(OPUS_LIBRARY opus
|
||||||
|
/usr/local/lib
|
||||||
|
/usr/lib
|
||||||
|
)
|
||||||
|
|
||||||
|
IF (OPUS_INCLUDE_DIR)
|
||||||
|
IF (OPUS_LIBRARY)
|
||||||
|
SET(OPUS_FOUND "YES")
|
||||||
|
ENDIF (OPUS_LIBRARY)
|
||||||
|
ENDIF (OPUS_INCLUDE_DIR)
|
||||||
|
|
||||||
|
MARK_AS_ADVANCED(
|
||||||
|
OPUS_INCLUDE_DIR
|
||||||
|
OPUS_LIBRARY
|
||||||
|
OPUS_FOUND
|
||||||
|
)
|
@ -1,8 +1,6 @@
|
|||||||
/**
|
/**
|
||||||
********************************************************************
|
********************************************************************
|
||||||
* @file psdk_osal.c
|
* @file osal.c
|
||||||
* @version V2.0.0
|
|
||||||
* @date 2019/07/01
|
|
||||||
* @brief
|
* @brief
|
||||||
*
|
*
|
||||||
* @copyright (c) 2021 DJI. All rights reserved.
|
* @copyright (c) 2021 DJI. All rights reserved.
|
||||||
@ -32,6 +30,10 @@
|
|||||||
|
|
||||||
/* Private types -------------------------------------------------------------*/
|
/* Private types -------------------------------------------------------------*/
|
||||||
|
|
||||||
|
/* Private values -------------------------------------------------------------*/
|
||||||
|
static uint32_t s_localTimeMsOffset = 0;
|
||||||
|
static uint64_t s_localTimeUsOffset = 0;
|
||||||
|
|
||||||
/* Private functions declaration ---------------------------------------------*/
|
/* Private functions declaration ---------------------------------------------*/
|
||||||
|
|
||||||
/* Exported functions definition ---------------------------------------------*/
|
/* Exported functions definition ---------------------------------------------*/
|
||||||
@ -281,6 +283,12 @@ T_DjiReturnCode Osal_GetTimeMs(uint32_t *ms)
|
|||||||
gettimeofday(&time, NULL);
|
gettimeofday(&time, NULL);
|
||||||
*ms = (time.tv_sec * 1000 + time.tv_usec / 1000);
|
*ms = (time.tv_sec * 1000 + time.tv_usec / 1000);
|
||||||
|
|
||||||
|
if (s_localTimeMsOffset == 0) {
|
||||||
|
s_localTimeMsOffset = *ms;
|
||||||
|
} else {
|
||||||
|
*ms = *ms - s_localTimeMsOffset;
|
||||||
|
}
|
||||||
|
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -291,15 +299,17 @@ T_DjiReturnCode Osal_GetTimeUs(uint64_t *us)
|
|||||||
gettimeofday(&time, NULL);
|
gettimeofday(&time, NULL);
|
||||||
*us = (time.tv_sec * 1000000 + time.tv_usec);
|
*us = (time.tv_sec * 1000000 + time.tv_usec);
|
||||||
|
|
||||||
|
if (s_localTimeUsOffset == 0) {
|
||||||
|
s_localTimeUsOffset = *us;
|
||||||
|
} else {
|
||||||
|
*us = *us - s_localTimeMsOffset;
|
||||||
|
}
|
||||||
|
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||||
}
|
}
|
||||||
|
|
||||||
void *Osal_Malloc(uint32_t size)
|
void *Osal_Malloc(uint32_t size)
|
||||||
{
|
{
|
||||||
if (size == 0) {
|
|
||||||
return NULL;
|
|
||||||
}
|
|
||||||
|
|
||||||
return malloc(size);
|
return malloc(size);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -7,19 +7,6 @@ set(CMAKE_C_COMPILER "gcc")
|
|||||||
set(CMAKE_CXX_COMPILER "g++")
|
set(CMAKE_CXX_COMPILER "g++")
|
||||||
add_definitions(-D_GNU_SOURCE)
|
add_definitions(-D_GNU_SOURCE)
|
||||||
|
|
||||||
# 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)
|
|
||||||
else()
|
|
||||||
message( STATUS "Did not find OpenCV in the system, image data is inside RecvContainer as raw data")
|
|
||||||
endif ()
|
|
||||||
|
|
||||||
set(COMMON_CXX_FLAGS "-std=c++11 -pthread")
|
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} ${COMMON_CXX_FLAGS} -fprofile-arcs -ftest-coverage -Wno-deprecated-declarations")
|
||||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fprofile-arcs -ftest-coverage")
|
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fprofile-arcs -ftest-coverage")
|
||||||
@ -50,31 +37,72 @@ else ()
|
|||||||
message(FATAL_ERROR "FATAL: Please confirm your platform.")
|
message(FATAL_ERROR "FATAL: Please confirm your platform.")
|
||||||
endif ()
|
endif ()
|
||||||
|
|
||||||
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR})
|
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/../common/3rdparty)
|
||||||
find_package(FFMPEG REQUIRED)
|
|
||||||
|
|
||||||
if(FFMPEG_FOUND)
|
|
||||||
message("Found FFMPEG FFMPEG_INCLUDE_DIR = ${FFMPEG_INCLUDE_DIR}")
|
|
||||||
message("Found FFMPEG FFMPEG_LIBRARIES = ${FFMPEG_LIBRARIES}")
|
|
||||||
else()
|
|
||||||
message("Cannot Find FFMPEG")
|
|
||||||
endif(FFMPEG_FOUND)
|
|
||||||
include_directories(${FFMPEG_INCLUDE_DIR})
|
|
||||||
include_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/include)
|
|
||||||
|
|
||||||
link_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/lib/${TOOLCHAIN_NAME})
|
link_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/lib/${TOOLCHAIN_NAME})
|
||||||
link_libraries(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/lib/${TOOLCHAIN_NAME}/libpayloadsdk.a -lstdc++)
|
link_libraries(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/lib/${TOOLCHAIN_NAME}/libpayloadsdk.a -lstdc++)
|
||||||
|
|
||||||
if (NOT EXECUTABLE_OUTPUT_PATH)
|
|
||||||
set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
|
|
||||||
endif ()
|
|
||||||
|
|
||||||
add_executable(${PROJECT_NAME}
|
add_executable(${PROJECT_NAME}
|
||||||
${MODULE_APP_SRC}
|
${MODULE_APP_SRC}
|
||||||
${MODULE_SAMPLE_SRC}
|
${MODULE_SAMPLE_SRC}
|
||||||
${MODULE_COMMON_SRC}
|
${MODULE_COMMON_SRC}
|
||||||
${MODULE_HAL_SRC})
|
${MODULE_HAL_SRC})
|
||||||
target_link_libraries(${PROJECT_NAME} m usb-1.0 ${FFMPEG_LIBRARIES})
|
|
||||||
|
# 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)
|
||||||
|
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}")
|
||||||
|
|
||||||
|
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}/../../../../../psdk_lib/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}
|
add_custom_command(TARGET ${PROJECT_NAME}
|
||||||
PRE_LINK COMMAND cmake ..
|
PRE_LINK COMMAND cmake ..
|
||||||
|
@ -64,28 +64,29 @@ int main(int argc, char **argv)
|
|||||||
start:
|
start:
|
||||||
std::cout
|
std::cout
|
||||||
<< "\n"
|
<< "\n"
|
||||||
<< "| Available commands: |\n"
|
<< "| Available commands: |\n"
|
||||||
<< "| [0] Fc subscribe sample - subscribe quaternion and gps data |\n"
|
<< "| [0] Fc subscribe sample - subscribe quaternion and gps data |\n"
|
||||||
<< "| [1] Flight controller sample - take off landing |\n"
|
<< "| [1] Flight controller sample - take off landing |\n"
|
||||||
<< "| [2] Flight controller sample - take off position ctrl landing |\n"
|
<< "| [2] Flight controller sample - take off position ctrl landing |\n"
|
||||||
<< "| [3] Flight controller sample - take off go home force landing |\n"
|
<< "| [3] Flight controller sample - take off go home force landing |\n"
|
||||||
<< "| [4] Flight controller sample - take off velocity ctrl landing |\n"
|
<< "| [4] Flight controller sample - take off velocity ctrl landing |\n"
|
||||||
<< "| [5] Flight controller sample - arrest flying |\n"
|
<< "| [5] Flight controller sample - arrest flying |\n"
|
||||||
<< "| [6] Flight controller sample - set get parameters |\n"
|
<< "| [6] Flight controller sample - set get parameters |\n"
|
||||||
<< "| [7] Hms info sample - get health manger system info |\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"
|
<< "| [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 (only support on M30/30T) |\n"
|
<< "| [9] Waypoint 3.0 sample - run airline mission by kmz file (only support on M30/30T) |\n"
|
||||||
<< "| [a] Gimbal manager sample - rotate gimbal on free mode |\n"
|
<< "| [a] Gimbal manager sample - rotate gimbal on free mode |\n"
|
||||||
<< "| [b] Gimbal manager sample - rotate gimbal on yaw follow mode |\n"
|
<< "| [b] Gimbal manager sample - rotate gimbal on yaw follow mode |\n"
|
||||||
<< "| [c] Camera stream view sample - display the camera video stream |\n"
|
<< "| [c] Camera stream view sample - display the camera video stream |\n"
|
||||||
<< "| [d] Stereo vision view sample - display the stereo image (only support on M300 RTK) |\n"
|
<< "| [d] Stereo vision view sample - display the stereo image (only support on M300 RTK) |\n"
|
||||||
<< "| [e] Start camera all feautes sample - you can operate the camera on DJI Pilot |\n"
|
<< "| [e] Start camera all feautes sample - you can operate the camera on DJI Pilot |\n"
|
||||||
<< "| [f] Start gimbal all feautes sample - you can operate the gimbal on DJI Pilot |\n"
|
<< "| [f] Start gimbal all feautes sample - you can operate the gimbal on DJI Pilot |\n"
|
||||||
<< "| [g] Start widget all feautes sample - you can operate the widget on DJI Pilot |\n"
|
<< "| [g] Start widget all feautes sample - you can operate the widget on DJI Pilot |\n"
|
||||||
<< "| [h] Start widget speaker sample - you can operate the speaker on MSDK demo |\n"
|
<< "| [h] Start widget speaker sample - you can operate the speaker on MSDK demo |\n"
|
||||||
<< "| [i] Start power management sample - you will see notification when aircraft power off |\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"
|
<< "| [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"
|
<< "| [l] Run camera manager sample - shoot photo by the selected camera mounted position |\n"
|
||||||
|
<< "| [m] Run camera manager download sample - download camera media file (only support on M300 RTK) |\n"
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
|
|
||||||
std::cin >> inputChar;
|
std::cin >> inputChar;
|
||||||
@ -206,6 +207,11 @@ start:
|
|||||||
DjiTest_CameraManagerRunSample(DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1,
|
DjiTest_CameraManagerRunSample(DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1,
|
||||||
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_SINGLE_PHOTO);
|
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_SINGLE_PHOTO);
|
||||||
break;
|
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);
|
||||||
|
break;
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -32,12 +32,16 @@
|
|||||||
|
|
||||||
#define LINUX_USB_BULK_EP_OUT "/dev/usb-ffs/bulk/ep1"
|
#define LINUX_USB_BULK_EP_OUT "/dev/usb-ffs/bulk/ep1"
|
||||||
#define LINUX_USB_BULK_EP_IN "/dev/usb-ffs/bulk/ep2"
|
#define LINUX_USB_BULK_EP_IN "/dev/usb-ffs/bulk/ep2"
|
||||||
#define LINUX_USB_PID (0x0955)
|
#define LINUX_USB_PID (0x7020)
|
||||||
#define LINUX_USB_VID (0x7020)
|
#define LINUX_USB_VID (0x0955)
|
||||||
|
|
||||||
/* Private types -------------------------------------------------------------*/
|
/* Private types -------------------------------------------------------------*/
|
||||||
typedef struct {
|
typedef struct {
|
||||||
|
#ifdef LIBUSB_INSTALLED
|
||||||
libusb_device_handle *handle;
|
libusb_device_handle *handle;
|
||||||
|
#else
|
||||||
|
void *handle;
|
||||||
|
#endif
|
||||||
int32_t ep1;
|
int32_t ep1;
|
||||||
int32_t ep2;
|
int32_t ep2;
|
||||||
T_DjiHalUsbBulkInfo usbBulkInfo;
|
T_DjiHalUsbBulkInfo usbBulkInfo;
|
||||||
@ -59,6 +63,7 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (usbBulkInfo.isUsbHost == true) {
|
if (usbBulkInfo.isUsbHost == true) {
|
||||||
|
#ifdef LIBUSB_INSTALLED
|
||||||
ret = libusb_init(NULL);
|
ret = libusb_init(NULL);
|
||||||
if (ret < 0) {
|
if (ret < 0) {
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||||
@ -78,7 +83,7 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan
|
|||||||
|
|
||||||
((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle;
|
((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle;
|
||||||
memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo));
|
memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo));
|
||||||
|
#endif
|
||||||
} else {
|
} else {
|
||||||
((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle;
|
((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle;
|
||||||
memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo));
|
memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo));
|
||||||
@ -109,9 +114,11 @@ T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle)
|
|||||||
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
||||||
|
|
||||||
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
||||||
|
#ifdef LIBUSB_INSTALLED
|
||||||
libusb_release_interface(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum);
|
libusb_release_interface(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum);
|
||||||
osalHandler->TaskSleepMs(100);
|
osalHandler->TaskSleepMs(100);
|
||||||
libusb_exit(NULL);
|
libusb_exit(NULL);
|
||||||
|
#endif
|
||||||
} else {
|
} else {
|
||||||
close(((T_HalUsbBulkObj *) usbBulkHandle)->ep1);
|
close(((T_HalUsbBulkObj *) usbBulkHandle)->ep1);
|
||||||
close(((T_HalUsbBulkObj *) usbBulkHandle)->ep2);
|
close(((T_HalUsbBulkObj *) usbBulkHandle)->ep2);
|
||||||
@ -136,18 +143,21 @@ T_DjiReturnCode HalUsbBulk_WriteData(T_DjiUsbBulkHandle usbBulkHandle, const uin
|
|||||||
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
||||||
|
|
||||||
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
||||||
|
#ifdef LIBUSB_INSTALLED
|
||||||
ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointOut,
|
ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointOut,
|
||||||
(uint8_t *) buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_TIMEOUT_MS);
|
(uint8_t *) buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_TIMEOUT_MS);
|
||||||
if (ret < 0) {
|
if (ret < 0) {
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
USER_LOG_ERROR("Write usb bulk data failed, errno = %d", ret);
|
||||||
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||||
}
|
}
|
||||||
|
|
||||||
*realLen = actualLen;
|
*realLen = actualLen;
|
||||||
|
#endif
|
||||||
} else {
|
} else {
|
||||||
*realLen = write(((T_HalUsbBulkObj *) usbBulkHandle)->ep1, buf, len);
|
*realLen = write(((T_HalUsbBulkObj *) usbBulkHandle)->ep1, buf, len);
|
||||||
}
|
}
|
||||||
|
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||||
}
|
}
|
||||||
|
|
||||||
T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len,
|
T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len,
|
||||||
@ -164,13 +174,16 @@ T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *b
|
|||||||
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
||||||
|
|
||||||
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
||||||
|
#ifdef LIBUSB_INSTALLED
|
||||||
ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointIn,
|
ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointIn,
|
||||||
buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_WAIT_FOREVER);
|
buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_WAIT_FOREVER);
|
||||||
if (ret < 0) {
|
if (ret < 0) {
|
||||||
|
USER_LOG_ERROR("Read usb bulk data failed, errno = %d", ret);
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||||
}
|
}
|
||||||
|
|
||||||
*realLen = actualLen;
|
*realLen = actualLen;
|
||||||
|
#endif
|
||||||
} else {
|
} else {
|
||||||
*realLen = read(((T_HalUsbBulkObj *) usbBulkHandle)->ep2, buf, len);
|
*realLen = read(((T_HalUsbBulkObj *) usbBulkHandle)->ep2, buf, len);
|
||||||
}
|
}
|
||||||
|
@ -189,11 +189,16 @@ T_DjiReturnCode DjiTest_CameraEmuMediaStartService(void)
|
|||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||||
}
|
}
|
||||||
|
|
||||||
returnCode = osalHandler->TaskCreate("user_camera_media_task", UserCameraMedia_SendVideoTask, 2048,
|
if (DjiPlatform_GetSocketHandler() != NULL) {
|
||||||
NULL, &s_userSendVideoThread);
|
returnCode = osalHandler->TaskCreate("user_camera_media_task", UserCameraMedia_SendVideoTask, 2048,
|
||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
NULL, &s_userSendVideoThread);
|
||||||
USER_LOG_ERROR("user send video task create error.");
|
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
USER_LOG_ERROR("user send video task create error.");
|
||||||
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
USER_LOG_WARN(
|
||||||
|
"Socket handler is null. Probably because socket handler is not be registered. Camera media sample may not be running.");
|
||||||
}
|
}
|
||||||
|
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||||
|
@ -31,8 +31,8 @@
|
|||||||
#include "dji_logger.h"
|
#include "dji_logger.h"
|
||||||
#include "dji_liveview.h"
|
#include "dji_liveview.h"
|
||||||
/* Private constants ---------------------------------------------------------*/
|
/* Private constants ---------------------------------------------------------*/
|
||||||
#define TEST_CAMERA_MANAGER_MEDIA_FILE_NAME_MAX_SIZE 32
|
#define TEST_CAMERA_MANAGER_MEDIA_FILE_NAME_MAX_SIZE 256
|
||||||
#define TEST_CAMERA_MANAGER_MEDIA_EXTEND_INFO_MAX_SIZE 128
|
#define TEST_CAMERA_MANAGER_MEDIA_DOWNLOAD_FILE_NUM 5
|
||||||
|
|
||||||
/* Private types -------------------------------------------------------------*/
|
/* Private types -------------------------------------------------------------*/
|
||||||
typedef struct {
|
typedef struct {
|
||||||
@ -53,10 +53,14 @@ static const T_DjiTestCameraTypeStr s_cameraTypeStrList[] = {
|
|||||||
{DJI_CAMERA_TYPE_L1, "Zenmuse L1"},
|
{DJI_CAMERA_TYPE_L1, "Zenmuse L1"},
|
||||||
{DJI_CAMERA_TYPE_M30, "Zenmuse M30"},
|
{DJI_CAMERA_TYPE_M30, "Zenmuse M30"},
|
||||||
{DJI_CAMERA_TYPE_M30T, "Zenmuse M30T"},
|
{DJI_CAMERA_TYPE_M30T, "Zenmuse M30T"},
|
||||||
|
{DJI_CAMERA_TYPE_H20N, "Zenmuse H20N"},
|
||||||
};
|
};
|
||||||
|
|
||||||
static FILE *s_downloadMediaFile = NULL;
|
static FILE *s_downloadMediaFile = NULL;
|
||||||
static T_DjiCameraManagerFileList s_meidaFileList;
|
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};
|
||||||
|
|
||||||
/* Private functions declaration ---------------------------------------------*/
|
/* Private functions declaration ---------------------------------------------*/
|
||||||
static uint8_t DjiTest_CameraManagerGetCameraTypeIndex(E_DjiCameraType cameraType);
|
static uint8_t DjiTest_CameraManagerGetCameraTypeIndex(E_DjiCameraType cameraType);
|
||||||
@ -817,7 +821,7 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition,
|
|||||||
mountPosition, returnCode);
|
mountPosition, returnCode);
|
||||||
goto exitCameraModule;
|
goto exitCameraModule;
|
||||||
}
|
}
|
||||||
USER_LOG_INFO("Mounted position %d camera's firmware is V%d.%d.%d.%d\r\n", mountPosition,
|
USER_LOG_INFO("Mounted position %d camera's firmware is V%02d.%02d.%02d.%02d\r\n", mountPosition,
|
||||||
firmwareVersion.firmware_version[0], firmwareVersion.firmware_version[1],
|
firmwareVersion.firmware_version[0], firmwareVersion.firmware_version[1],
|
||||||
firmwareVersion.firmware_version[2], firmwareVersion.firmware_version[3]);
|
firmwareVersion.firmware_version[2], firmwareVersion.firmware_version[3]);
|
||||||
|
|
||||||
@ -850,7 +854,8 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition,
|
|||||||
case E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_SHUTTER_SPEED: {
|
case E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_SHUTTER_SPEED: {
|
||||||
USER_LOG_INFO("--> Function a: Set camera shutter speed to 1/100 s");
|
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");
|
DjiTest_WidgetLogAppend("--> Function a: Set camera shutter speed to 1/100 s");
|
||||||
if (cameraType == DJI_CAMERA_TYPE_H20 || cameraType == DJI_CAMERA_TYPE_H20T) {
|
if (cameraType == DJI_CAMERA_TYPE_H20 || cameraType == DJI_CAMERA_TYPE_H20T ||
|
||||||
|
cameraType == DJI_CAMERA_TYPE_M30 || cameraType == DJI_CAMERA_TYPE_M30T) {
|
||||||
USER_LOG_INFO("Set mounted position %d camera's exposure mode to manual mode.",
|
USER_LOG_INFO("Set mounted position %d camera's exposure mode to manual mode.",
|
||||||
mountPosition);
|
mountPosition);
|
||||||
returnCode = DjiTest_CameraManagerSetExposureMode(mountPosition,
|
returnCode = DjiTest_CameraManagerSetExposureMode(mountPosition,
|
||||||
@ -886,7 +891,8 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition,
|
|||||||
case E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_APERTURE: {
|
case E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_APERTURE: {
|
||||||
USER_LOG_INFO("--> Function b: Set camera aperture to 400(F/4)");
|
USER_LOG_INFO("--> Function b: Set camera aperture to 400(F/4)");
|
||||||
DjiTest_WidgetLogAppend("--> 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) {
|
if (cameraType == DJI_CAMERA_TYPE_H20 || cameraType == DJI_CAMERA_TYPE_H20T
|
||||||
|
|| cameraType == DJI_CAMERA_TYPE_M30 || cameraType == DJI_CAMERA_TYPE_M30T) {
|
||||||
USER_LOG_INFO("Set mounted position %d camera's exposure mode to manual mode.",
|
USER_LOG_INFO("Set mounted position %d camera's exposure mode to manual mode.",
|
||||||
mountPosition);
|
mountPosition);
|
||||||
returnCode = DjiTest_CameraManagerSetExposureMode(mountPosition,
|
returnCode = DjiTest_CameraManagerSetExposureMode(mountPosition,
|
||||||
@ -1188,12 +1194,7 @@ static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_Dj
|
|||||||
{
|
{
|
||||||
T_DjiReturnCode returnCode;
|
T_DjiReturnCode returnCode;
|
||||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||||
|
uint16_t downloadCount = 0;
|
||||||
returnCode = DjiCameraManager_DownloadFileList(position, &s_meidaFileList);
|
|
||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
|
||||||
USER_LOG_ERROR("Download file list failed, error code: 0x%08X.", returnCode);
|
|
||||||
return returnCode;
|
|
||||||
}
|
|
||||||
|
|
||||||
returnCode = DjiCameraManager_RegDownloadFileDataCallback(position, DjiTest_CameraManagerDownloadFileDataCallback);
|
returnCode = DjiCameraManager_RegDownloadFileDataCallback(position, DjiTest_CameraManagerDownloadFileDataCallback);
|
||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||||
@ -1201,11 +1202,21 @@ static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_Dj
|
|||||||
return returnCode;
|
return returnCode;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
returnCode = DjiCameraManager_DownloadFileList(position, &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) {
|
if (s_meidaFileList.totalCount > 0) {
|
||||||
for (int i = 0; i < s_meidaFileList.totalCount; ++i) {
|
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) {
|
if (s_meidaFileList.fileListInfo[i].fileSize < 1 * 1024 * 1024) {
|
||||||
USER_LOG_INFO(
|
printf(
|
||||||
"Media file_%03d name: %s, index: %d, time:%04d-%02d-%02d_%02d:%02d:%02d, size: %.2f KB, type: %d",
|
"\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,
|
i, s_meidaFileList.fileListInfo[i].fileName,
|
||||||
s_meidaFileList.fileListInfo[i].fileIndex,
|
s_meidaFileList.fileListInfo[i].fileIndex,
|
||||||
s_meidaFileList.fileListInfo[i].createTime.year,
|
s_meidaFileList.fileListInfo[i].createTime.year,
|
||||||
@ -1217,8 +1228,8 @@ static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_Dj
|
|||||||
(dji_f32_t) s_meidaFileList.fileListInfo[i].fileSize / 1024,
|
(dji_f32_t) s_meidaFileList.fileListInfo[i].fileSize / 1024,
|
||||||
s_meidaFileList.fileListInfo[i].type);
|
s_meidaFileList.fileListInfo[i].type);
|
||||||
} else {
|
} else {
|
||||||
USER_LOG_INFO(
|
printf(
|
||||||
"Media file_%03d name: %s, index: %d, time:%04d-%02d-%02d_%02d:%02d:%02d, size: %.2f MB, type: %d",
|
"\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,
|
i, s_meidaFileList.fileListInfo[i].fileName,
|
||||||
s_meidaFileList.fileListInfo[i].fileIndex,
|
s_meidaFileList.fileListInfo[i].fileIndex,
|
||||||
s_meidaFileList.fileListInfo[i].createTime.year,
|
s_meidaFileList.fileListInfo[i].createTime.year,
|
||||||
@ -1231,16 +1242,23 @@ static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_Dj
|
|||||||
s_meidaFileList.fileListInfo[i].type);
|
s_meidaFileList.fileListInfo[i].type);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
printf("\r\n");
|
||||||
|
|
||||||
osalHandler->TaskSleepMs(1000);
|
osalHandler->TaskSleepMs(1000);
|
||||||
|
|
||||||
returnCode = DjiCameraManager_DownloadFileByIndex(position, s_meidaFileList.fileListInfo[0].fileIndex);
|
if (s_meidaFileList.totalCount < TEST_CAMERA_MANAGER_MEDIA_DOWNLOAD_FILE_NUM) {
|
||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
downloadCount = s_meidaFileList.totalCount;
|
||||||
USER_LOG_ERROR("Download media file by index failed, error code: 0x%08X.", returnCode);
|
} else {
|
||||||
return returnCode;
|
downloadCount = TEST_CAMERA_MANAGER_MEDIA_DOWNLOAD_FILE_NUM;
|
||||||
}
|
}
|
||||||
|
|
||||||
osalHandler->TaskSleepMs(1000);
|
for (int i = 0; i < downloadCount; ++i) {
|
||||||
|
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);
|
||||||
|
return returnCode;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
returnCode = DjiCameraManager_DeleteFileByIndex(position, s_meidaFileList.fileListInfo[0].fileIndex);
|
returnCode = DjiCameraManager_DeleteFileByIndex(position, s_meidaFileList.fileListInfo[0].fileIndex);
|
||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||||
@ -1250,7 +1268,7 @@ static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_Dj
|
|||||||
|
|
||||||
osalHandler->TaskSleepMs(1000);
|
osalHandler->TaskSleepMs(1000);
|
||||||
} else {
|
} else {
|
||||||
USER_LOG_WARN("Media file is not existed in sdcard.");
|
USER_LOG_WARN("Media file is not existed in sdcard.\r\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||||
@ -1259,11 +1277,9 @@ static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_Dj
|
|||||||
static T_DjiReturnCode DjiTest_CameraManagerDownloadFileDataCallback(T_DjiDownloadFilePacketInfo packetInfo,
|
static T_DjiReturnCode DjiTest_CameraManagerDownloadFileDataCallback(T_DjiDownloadFilePacketInfo packetInfo,
|
||||||
const uint8_t *data, uint16_t len)
|
const uint8_t *data, uint16_t len)
|
||||||
{
|
{
|
||||||
char fileName[TEST_CAMERA_MANAGER_MEDIA_FILE_NAME_MAX_SIZE];
|
|
||||||
char extendInfo[TEST_CAMERA_MANAGER_MEDIA_EXTEND_INFO_MAX_SIZE];
|
|
||||||
int32_t i;
|
int32_t i;
|
||||||
|
float downloadSpeed = 0.0f;
|
||||||
sprintf(extendInfo, " FileIndex: %d", packetInfo.fileIndex);
|
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||||
|
|
||||||
if (packetInfo.downloadFileEvent == DJI_DOWNLOAD_FILE_EVENT_START) {
|
if (packetInfo.downloadFileEvent == DJI_DOWNLOAD_FILE_EVENT_START) {
|
||||||
for (i = 0; i < s_meidaFileList.totalCount; ++i) {
|
for (i = 0; i < s_meidaFileList.totalCount; ++i) {
|
||||||
@ -1271,9 +1287,12 @@ static T_DjiReturnCode DjiTest_CameraManagerDownloadFileDataCallback(T_DjiDownlo
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
sprintf(fileName, "%s", s_meidaFileList.fileListInfo[i].fileName);
|
osalHandler->GetTimeMs(&downloadStartMs);
|
||||||
USER_LOG_INFO("Start download media file %s", s_meidaFileList.fileListInfo[i].fileName);
|
|
||||||
s_downloadMediaFile = fopen(fileName, "wb+");
|
memset(downloadFileName, 0, sizeof(downloadFileName));
|
||||||
|
snprintf(downloadFileName, sizeof(downloadFileName), "%s", s_meidaFileList.fileListInfo[i].fileName);
|
||||||
|
USER_LOG_INFO("Start download media file");
|
||||||
|
s_downloadMediaFile = fopen(downloadFileName, "wb+");
|
||||||
if (s_downloadMediaFile == NULL) {
|
if (s_downloadMediaFile == NULL) {
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||||
}
|
}
|
||||||
@ -1282,13 +1301,24 @@ static T_DjiReturnCode DjiTest_CameraManagerDownloadFileDataCallback(T_DjiDownlo
|
|||||||
if (s_downloadMediaFile != NULL) {
|
if (s_downloadMediaFile != NULL) {
|
||||||
fwrite(data, 1, len, s_downloadMediaFile);
|
fwrite(data, 1, len, s_downloadMediaFile);
|
||||||
}
|
}
|
||||||
|
printf("\033[1;32;40m ### [Complete rate : %0.1f%%] (%s), size: %d, fileIndex: %d\033[0m\r\n",
|
||||||
|
packetInfo.progressInPercent, downloadFileName, packetInfo.fileSize, packetInfo.fileIndex);
|
||||||
|
printf("\033[1A");
|
||||||
|
USER_LOG_DEBUG("Transfer download media file data, len: %d, percent: %.1f", len, packetInfo.progressInPercent);
|
||||||
} else if (packetInfo.downloadFileEvent == DJI_DOWNLOAD_FILE_EVENT_END) {
|
} else if (packetInfo.downloadFileEvent == DJI_DOWNLOAD_FILE_EVENT_END) {
|
||||||
if (s_downloadMediaFile != NULL) {
|
if (s_downloadMediaFile != NULL) {
|
||||||
fwrite(data, 1, len, s_downloadMediaFile);
|
fwrite(data, 1, len, s_downloadMediaFile);
|
||||||
}
|
}
|
||||||
|
osalHandler->GetTimeMs(&downloadEndMs);
|
||||||
|
|
||||||
USER_LOG_INFO("End download media file");
|
downloadSpeed = (float) packetInfo.fileSize / (float) (downloadEndMs - downloadStartMs);
|
||||||
|
printf("\033[1;32;40m ### [Complete rate : %0.1f%%] (%s), size: %d, fileIndex: %d\033[0m\r\n",
|
||||||
|
packetInfo.progressInPercent, downloadFileName, packetInfo.fileSize, packetInfo.fileIndex);
|
||||||
|
printf("\033[1A");
|
||||||
|
printf("\r\n");
|
||||||
|
USER_LOG_INFO("End download media file, Download Speed %.2f KB/S\r\n\r\n", downloadSpeed);
|
||||||
fclose(s_downloadMediaFile);
|
fclose(s_downloadMediaFile);
|
||||||
|
s_downloadMediaFile = NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||||
|
@ -156,8 +156,9 @@ T_DjiReturnCode DjiTest_FcSubscriptionRunSample(void)
|
|||||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||||
USER_LOG_ERROR("get value of topic velocity error.");
|
USER_LOG_ERROR("get value of topic velocity error.");
|
||||||
} else {
|
} else {
|
||||||
USER_LOG_INFO("velocity: x = %f y = %f z = %f healthFlag = %d.", velocity.data.x, velocity.data.y,
|
USER_LOG_INFO("velocity: x = %f y = %f z = %f healthFlag = %d, timestamp ms = %d us = %d.", velocity.data.x,
|
||||||
velocity.data.z, velocity.health);
|
velocity.data.y,
|
||||||
|
velocity.data.z, velocity.health, timestamp.millisecond, timestamp.microsecond);
|
||||||
}
|
}
|
||||||
|
|
||||||
djiStat = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_GPS_POSITION,
|
djiStat = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_GPS_POSITION,
|
||||||
|
@ -30,6 +30,7 @@
|
|||||||
#include "dji_logger.h"
|
#include "dji_logger.h"
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include <widget_interaction_test/test_widget_interaction.h>
|
#include <widget_interaction_test/test_widget_interaction.h>
|
||||||
|
#include <dji_aircraft_info.h>
|
||||||
/* Private constants ---------------------------------------------------------*/
|
/* Private constants ---------------------------------------------------------*/
|
||||||
|
|
||||||
/* Private types -------------------------------------------------------------*/
|
/* Private types -------------------------------------------------------------*/
|
||||||
@ -665,6 +666,12 @@ void DjiTest_FlightControlSetGetParamSample()
|
|||||||
E_DjiFlightControllerGoHomeAltitude goHomeAltitude;
|
E_DjiFlightControllerGoHomeAltitude goHomeAltitude;
|
||||||
E_DjiFlightControllerRtkPositionEnableStatus rtkEnableStatus;
|
E_DjiFlightControllerRtkPositionEnableStatus rtkEnableStatus;
|
||||||
E_DjiFlightControllerRCLostAction rcLostAction;
|
E_DjiFlightControllerRCLostAction rcLostAction;
|
||||||
|
T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo;
|
||||||
|
|
||||||
|
returnCode = DjiAircraftInfo_GetBaseInfo(&aircraftInfoBaseInfo);
|
||||||
|
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||||
|
USER_LOG_ERROR("get aircraft base info error");
|
||||||
|
}
|
||||||
|
|
||||||
USER_LOG_INFO("Flight control set-get-param sample start");
|
USER_LOG_INFO("Flight control set-get-param sample start");
|
||||||
DjiTest_WidgetLogAppend("Flight control set-get-param sample start");
|
DjiTest_WidgetLogAppend("Flight control set-get-param sample start");
|
||||||
@ -823,25 +830,27 @@ void DjiTest_FlightControlSetGetParamSample()
|
|||||||
s_osalHandler->TaskSleepMs(1000);
|
s_osalHandler->TaskSleepMs(1000);
|
||||||
|
|
||||||
/*! Set rc lost action */
|
/*! Set rc lost action */
|
||||||
USER_LOG_INFO("--> Step 15: Set rc lost action");
|
if (aircraftInfoBaseInfo.aircraftType != DJI_AIRCRAFT_TYPE_M300_RTK) {
|
||||||
DjiTest_WidgetLogAppend("--> Step 15: Set rc lost action");
|
USER_LOG_INFO("--> Step 15: Set rc lost action");
|
||||||
returnCode = DjiFlightController_SetRCLostAction(DJI_FLIGHT_CONTROLLER_RC_LOST_ACTION_GOHOME);
|
DjiTest_WidgetLogAppend("--> Step 15: Set rc lost action");
|
||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
returnCode = DjiFlightController_SetRCLostAction(DJI_FLIGHT_CONTROLLER_RC_LOST_ACTION_GOHOME);
|
||||||
USER_LOG_ERROR("Set rc lost action failed, error code: 0x%08X", returnCode);
|
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||||
goto out;
|
USER_LOG_ERROR("Set rc lost action failed, error code: 0x%08X", returnCode);
|
||||||
}
|
goto out;
|
||||||
s_osalHandler->TaskSleepMs(1000);
|
}
|
||||||
|
s_osalHandler->TaskSleepMs(1000);
|
||||||
|
|
||||||
USER_LOG_INFO("--> Step 16: Get rc lost action\r\n");
|
USER_LOG_INFO("--> Step 16: Get rc lost action\r\n");
|
||||||
DjiTest_WidgetLogAppend("--> Step 16: Get rc lost action\r\n");
|
DjiTest_WidgetLogAppend("--> Step 16: Get rc lost action\r\n");
|
||||||
returnCode = DjiFlightController_GetRCLostAction(&rcLostAction);
|
returnCode = DjiFlightController_GetRCLostAction(&rcLostAction);
|
||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||||
USER_LOG_ERROR("Get rc lost action failed, error code: 0x%08X", returnCode);
|
USER_LOG_ERROR("Get rc lost action failed, error code: 0x%08X", returnCode);
|
||||||
goto out;
|
goto out;
|
||||||
|
}
|
||||||
|
USER_LOG_INFO("Current rc lost action is %d\r\n", rcLostAction);
|
||||||
|
DjiTest_WidgetLogAppend("Current rc lost action is %d\r\n", rcLostAction);
|
||||||
|
s_osalHandler->TaskSleepMs(1000);
|
||||||
}
|
}
|
||||||
USER_LOG_INFO("Current rc lost action is %d\r\n", rcLostAction);
|
|
||||||
DjiTest_WidgetLogAppend("Current rc lost action is %d\r\n", rcLostAction);
|
|
||||||
s_osalHandler->TaskSleepMs(1000);
|
|
||||||
|
|
||||||
out:
|
out:
|
||||||
USER_LOG_INFO("Flight control set-get-param sample end");
|
USER_LOG_INFO("Flight control set-get-param sample end");
|
||||||
|
@ -67,4 +67,4 @@ T_DjiReturnCode UtilFile_GetFileData(FILE *file, uint32_t offset, uint16_t len,
|
|||||||
|
|
||||||
#endif // UTIL_FILE_H
|
#endif // UTIL_FILE_H
|
||||||
|
|
||||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||||
|
@ -36,7 +36,7 @@
|
|||||||
|
|
||||||
#ifdef OPUS_INSTALLED
|
#ifdef OPUS_INSTALLED
|
||||||
|
|
||||||
#include <opus.h>
|
#include <opus/opus.h>
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -80,13 +80,10 @@ static bool s_isDecodeFinished = true;
|
|||||||
static void SetSpeakerState(E_DjiWidgetSpeakerState speakerState);
|
static void SetSpeakerState(E_DjiWidgetSpeakerState speakerState);
|
||||||
static T_DjiReturnCode GetSpeakerState(T_DjiWidgetSpeakerState *speakerState);
|
static T_DjiReturnCode GetSpeakerState(T_DjiWidgetSpeakerState *speakerState);
|
||||||
static T_DjiReturnCode SetWorkMode(E_DjiWidgetSpeakerWorkMode workMode);
|
static T_DjiReturnCode SetWorkMode(E_DjiWidgetSpeakerWorkMode workMode);
|
||||||
static T_DjiReturnCode GetWorkMode(E_DjiWidgetSpeakerWorkMode *workMode);
|
|
||||||
static T_DjiReturnCode SetPlayMode(E_DjiWidgetSpeakerPlayMode playMode);
|
static T_DjiReturnCode SetPlayMode(E_DjiWidgetSpeakerPlayMode playMode);
|
||||||
static T_DjiReturnCode GetPlayMode(E_DjiWidgetSpeakerPlayMode *playMode);
|
|
||||||
static T_DjiReturnCode StartPlay(void);
|
static T_DjiReturnCode StartPlay(void);
|
||||||
static T_DjiReturnCode StopPlay(void);
|
static T_DjiReturnCode StopPlay(void);
|
||||||
static T_DjiReturnCode SetVolume(uint8_t volume);
|
static T_DjiReturnCode SetVolume(uint8_t volume);
|
||||||
static T_DjiReturnCode GetVolume(uint8_t *volume);
|
|
||||||
static T_DjiReturnCode ReceiveTtsData(E_DjiWidgetTransmitDataEvent event,
|
static T_DjiReturnCode ReceiveTtsData(E_DjiWidgetTransmitDataEvent event,
|
||||||
uint32_t offset, uint8_t *buf, uint16_t size);
|
uint32_t offset, uint8_t *buf, uint16_t size);
|
||||||
static T_DjiReturnCode ReceiveAudioData(E_DjiWidgetTransmitDataEvent event,
|
static T_DjiReturnCode ReceiveAudioData(E_DjiWidgetTransmitDataEvent event,
|
||||||
@ -107,13 +104,10 @@ T_DjiReturnCode DjiTest_WidgetSpeakerStartService(void)
|
|||||||
|
|
||||||
s_speakerHandler.GetSpeakerState = GetSpeakerState;
|
s_speakerHandler.GetSpeakerState = GetSpeakerState;
|
||||||
s_speakerHandler.SetWorkMode = SetWorkMode;
|
s_speakerHandler.SetWorkMode = SetWorkMode;
|
||||||
s_speakerHandler.GetWorkMode = GetWorkMode;
|
|
||||||
s_speakerHandler.StartPlay = StartPlay;
|
s_speakerHandler.StartPlay = StartPlay;
|
||||||
s_speakerHandler.StopPlay = StopPlay;
|
s_speakerHandler.StopPlay = StopPlay;
|
||||||
s_speakerHandler.SetPlayMode = SetPlayMode;
|
s_speakerHandler.SetPlayMode = SetPlayMode;
|
||||||
s_speakerHandler.GetPlayMode = GetPlayMode;
|
|
||||||
s_speakerHandler.SetVolume = SetVolume;
|
s_speakerHandler.SetVolume = SetVolume;
|
||||||
s_speakerHandler.GetVolume = GetVolume;
|
|
||||||
s_speakerHandler.ReceiveTtsData = ReceiveTtsData;
|
s_speakerHandler.ReceiveTtsData = ReceiveTtsData;
|
||||||
s_speakerHandler.ReceiveVoiceData = ReceiveAudioData;
|
s_speakerHandler.ReceiveVoiceData = ReceiveAudioData;
|
||||||
|
|
||||||
@ -322,12 +316,13 @@ static T_DjiReturnCode DjiTest_PlayTtsData(void)
|
|||||||
|
|
||||||
SetSpeakerState(DJI_WIDGET_SPEAKER_STATE_IN_TTS_CONVERSION);
|
SetSpeakerState(DJI_WIDGET_SPEAKER_STATE_IN_TTS_CONVERSION);
|
||||||
|
|
||||||
#ifdef EKHO_INSTALLED
|
#if EKHO_INSTALLED
|
||||||
/*! Attention: you can use other tts opensource function to convert txt to speech, example used ekho v7.5 */
|
/*! Attention: you can use other tts opensource function to convert txt to speech, example used ekho v7.5 */
|
||||||
snprintf(cmdStr, sizeof(cmdStr), " ekho %s -s 20 -p 20 -a 100", data);
|
snprintf(cmdStr, sizeof(cmdStr), " ekho %s -s 20 -p 20 -a 100 -o %s", data, WIDGET_SPEAKER_TTS_OUTPUT_FILE_NAME);
|
||||||
#else
|
#else
|
||||||
snprintf(cmdStr, sizeof(cmdStr), "tts_offline_sample '%s' %s", data,
|
USER_LOG_WARN(
|
||||||
WIDGET_SPEAKER_TTS_OUTPUT_FILE_NAME);
|
"Ekho is not installed, please visit https://www.eguidedog.net/ekho.php to install it or use other TTS tools to convert audio");
|
||||||
|
#endif
|
||||||
DjiUserUtil_RunSystemCmd(cmdStr);
|
DjiUserUtil_RunSystemCmd(cmdStr);
|
||||||
|
|
||||||
SetSpeakerState(DJI_WIDGET_SPEAKER_STATE_PLAYING);
|
SetSpeakerState(DJI_WIDGET_SPEAKER_STATE_PLAYING);
|
||||||
@ -335,7 +330,6 @@ static T_DjiReturnCode DjiTest_PlayTtsData(void)
|
|||||||
memset(cmdStr, 0, sizeof(cmdStr));
|
memset(cmdStr, 0, sizeof(cmdStr));
|
||||||
snprintf(cmdStr, sizeof(cmdStr), "ffplay -nodisp -autoexit -ar 16000 -ac 1 -f s16le -i %s 2>/dev/null",
|
snprintf(cmdStr, sizeof(cmdStr), "ffplay -nodisp -autoexit -ar 16000 -ac 1 -f s16le -i %s 2>/dev/null",
|
||||||
WIDGET_SPEAKER_TTS_OUTPUT_FILE_NAME);
|
WIDGET_SPEAKER_TTS_OUTPUT_FILE_NAME);
|
||||||
#endif
|
|
||||||
|
|
||||||
return DjiUserUtil_RunSystemCmd(cmdStr);
|
return DjiUserUtil_RunSystemCmd(cmdStr);
|
||||||
}
|
}
|
||||||
@ -453,28 +447,6 @@ static T_DjiReturnCode SetWorkMode(E_DjiWidgetSpeakerWorkMode workMode)
|
|||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||||
}
|
}
|
||||||
|
|
||||||
static T_DjiReturnCode GetWorkMode(E_DjiWidgetSpeakerWorkMode *workMode)
|
|
||||||
{
|
|
||||||
T_DjiReturnCode returnCode;
|
|
||||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
|
||||||
|
|
||||||
returnCode = osalHandler->MutexLock(s_speakerMutex);
|
|
||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
|
||||||
USER_LOG_ERROR("lock mutex error: 0x%08llX.", returnCode);
|
|
||||||
return returnCode;
|
|
||||||
}
|
|
||||||
|
|
||||||
*workMode = s_speakerState.workMode;
|
|
||||||
|
|
||||||
returnCode = osalHandler->MutexUnlock(s_speakerMutex);
|
|
||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
|
||||||
USER_LOG_ERROR("unlock mutex error: 0x%08llX.", returnCode);
|
|
||||||
return returnCode;
|
|
||||||
}
|
|
||||||
|
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
|
||||||
}
|
|
||||||
|
|
||||||
static T_DjiReturnCode SetPlayMode(E_DjiWidgetSpeakerPlayMode playMode)
|
static T_DjiReturnCode SetPlayMode(E_DjiWidgetSpeakerPlayMode playMode)
|
||||||
{
|
{
|
||||||
T_DjiReturnCode returnCode;
|
T_DjiReturnCode returnCode;
|
||||||
@ -498,28 +470,6 @@ static T_DjiReturnCode SetPlayMode(E_DjiWidgetSpeakerPlayMode playMode)
|
|||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||||
}
|
}
|
||||||
|
|
||||||
static T_DjiReturnCode GetPlayMode(E_DjiWidgetSpeakerPlayMode *playMode)
|
|
||||||
{
|
|
||||||
T_DjiReturnCode returnCode;
|
|
||||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
|
||||||
|
|
||||||
returnCode = osalHandler->MutexLock(s_speakerMutex);
|
|
||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
|
||||||
USER_LOG_ERROR("lock mutex error: 0x%08llX.", returnCode);
|
|
||||||
return returnCode;
|
|
||||||
}
|
|
||||||
|
|
||||||
*playMode = s_speakerState.playMode;
|
|
||||||
|
|
||||||
returnCode = osalHandler->MutexUnlock(s_speakerMutex);
|
|
||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
|
||||||
USER_LOG_ERROR("unlock mutex error: 0x%08llX.", returnCode);
|
|
||||||
return returnCode;
|
|
||||||
}
|
|
||||||
|
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
|
||||||
}
|
|
||||||
|
|
||||||
static T_DjiReturnCode StartPlay(void)
|
static T_DjiReturnCode StartPlay(void)
|
||||||
{
|
{
|
||||||
uint32_t pid;
|
uint32_t pid;
|
||||||
@ -581,9 +531,10 @@ static T_DjiReturnCode SetVolume(uint8_t volume)
|
|||||||
}
|
}
|
||||||
|
|
||||||
realVolume = 1.5f * (float) volume;
|
realVolume = 1.5f * (float) volume;
|
||||||
USER_LOG_INFO("Set widget speaker volume: %d", volume);
|
|
||||||
s_speakerState.volume = volume;
|
s_speakerState.volume = volume;
|
||||||
|
|
||||||
|
#ifdef PLATFORM_ARCH_x86_64
|
||||||
|
USER_LOG_INFO("Set widget speaker volume: %d", volume);
|
||||||
memset(cmdStr, 0, sizeof(cmdStr));
|
memset(cmdStr, 0, sizeof(cmdStr));
|
||||||
snprintf(cmdStr, sizeof(cmdStr), "pactl set-sink-volume %s %d%%", WIDGET_SPEAKER_USB_AUDIO_DEVICE_NAME,
|
snprintf(cmdStr, sizeof(cmdStr), "pactl set-sink-volume %s %d%%", WIDGET_SPEAKER_USB_AUDIO_DEVICE_NAME,
|
||||||
(int32_t) realVolume);
|
(int32_t) realVolume);
|
||||||
@ -592,28 +543,9 @@ static T_DjiReturnCode SetVolume(uint8_t volume)
|
|||||||
if (returnCode < 0) {
|
if (returnCode < 0) {
|
||||||
USER_LOG_ERROR("Set widget speaker volume error: %d", ret);
|
USER_LOG_ERROR("Set widget speaker volume error: %d", ret);
|
||||||
}
|
}
|
||||||
|
#else
|
||||||
returnCode = osalHandler->MutexUnlock(s_speakerMutex);
|
USER_LOG_WARN("Add set speaker volume function here!");
|
||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
#endif
|
||||||
USER_LOG_ERROR("unlock mutex error: 0x%08llX.", returnCode);
|
|
||||||
return returnCode;
|
|
||||||
}
|
|
||||||
|
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
|
||||||
}
|
|
||||||
|
|
||||||
static T_DjiReturnCode GetVolume(uint8_t *volume)
|
|
||||||
{
|
|
||||||
T_DjiReturnCode returnCode;
|
|
||||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
|
||||||
|
|
||||||
returnCode = osalHandler->MutexLock(s_speakerMutex);
|
|
||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
|
||||||
USER_LOG_ERROR("lock mutex error: 0x%08llX.", returnCode);
|
|
||||||
return returnCode;
|
|
||||||
}
|
|
||||||
|
|
||||||
*volume = s_speakerState.volume;
|
|
||||||
|
|
||||||
returnCode = osalHandler->MutexUnlock(s_speakerMutex);
|
returnCode = osalHandler->MutexUnlock(s_speakerMutex);
|
||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||||
@ -737,7 +669,7 @@ static void *DjiTest_WidgetSpeakerTask(void *arg)
|
|||||||
if (s_speakerState.state == DJI_WIDGET_SPEAKER_STATE_PLAYING) {
|
if (s_speakerState.state == DJI_WIDGET_SPEAKER_STATE_PLAYING) {
|
||||||
if (s_speakerState.playMode == DJI_WIDGET_SPEAKER_PLAY_MODE_LOOP_PLAYBACK) {
|
if (s_speakerState.playMode == DJI_WIDGET_SPEAKER_PLAY_MODE_LOOP_PLAYBACK) {
|
||||||
if (s_speakerState.workMode == DJI_WIDGET_SPEAKER_WORK_MODE_VOICE) {
|
if (s_speakerState.workMode == DJI_WIDGET_SPEAKER_WORK_MODE_VOICE) {
|
||||||
USER_LOG_WARN("Waiting opus decoder finished...");
|
USER_LOG_DEBUG("Waiting opus decoder finished...");
|
||||||
while (s_isDecodeFinished == false) {
|
while (s_isDecodeFinished == false) {
|
||||||
osalHandler->TaskSleepMs(1);
|
osalHandler->TaskSleepMs(1);
|
||||||
}
|
}
|
||||||
@ -754,7 +686,7 @@ static void *DjiTest_WidgetSpeakerTask(void *arg)
|
|||||||
osalHandler->TaskSleepMs(1000);
|
osalHandler->TaskSleepMs(1000);
|
||||||
} else {
|
} else {
|
||||||
if (s_speakerState.workMode == DJI_WIDGET_SPEAKER_WORK_MODE_VOICE) {
|
if (s_speakerState.workMode == DJI_WIDGET_SPEAKER_WORK_MODE_VOICE) {
|
||||||
USER_LOG_WARN("Waiting opus decoder finished...");
|
USER_LOG_DEBUG("Waiting opus decoder finished...");
|
||||||
while (s_isDecodeFinished == false) {
|
while (s_isDecodeFinished == false) {
|
||||||
osalHandler->TaskSleepMs(1);
|
osalHandler->TaskSleepMs(1);
|
||||||
}
|
}
|
||||||
|
@ -7,6 +7,10 @@
|
|||||||
"floating_window": {
|
"floating_window": {
|
||||||
"is_enable": true
|
"is_enable": true
|
||||||
},
|
},
|
||||||
|
"speaker": {
|
||||||
|
"is_enable_tts": true,
|
||||||
|
"is_enable_voice": true
|
||||||
|
},
|
||||||
"widget_list": [
|
"widget_list": [
|
||||||
{
|
{
|
||||||
"widget_index": 0,
|
"widget_index": 0,
|
||||||
|
@ -7,6 +7,10 @@
|
|||||||
"floating_window": {
|
"floating_window": {
|
||||||
"is_enable": true
|
"is_enable": true
|
||||||
},
|
},
|
||||||
|
"speaker": {
|
||||||
|
"is_enable_tts": true,
|
||||||
|
"is_enable_voice": true
|
||||||
|
},
|
||||||
"widget_list": [
|
"widget_list": [
|
||||||
{
|
{
|
||||||
"widget_index": 0,
|
"widget_index": 0,
|
||||||
|
34
samples/sample_c/platform/linux/common/3rdparty/FindLIBUSB.cmake
vendored
Normal file
34
samples/sample_c/platform/linux/common/3rdparty/FindLIBUSB.cmake
vendored
Normal file
@ -0,0 +1,34 @@
|
|||||||
|
#
|
||||||
|
# Find the native LIBUSB includes and library
|
||||||
|
#
|
||||||
|
# This module defines
|
||||||
|
# LIBUSB_INCLUDE_DIR, where to find libusb.h
|
||||||
|
# LIBUSB_LIBRARY, the libraries to link against to use LIBUSB.
|
||||||
|
# LIBUSB_FOUND, If false, do not try to use LIBUSB.
|
||||||
|
|
||||||
|
FIND_PATH(LIBUSB_INCLUDE_DIR libusb.h
|
||||||
|
PATHS
|
||||||
|
/usr/local/include/libusb-1.0
|
||||||
|
/usr/include/libusb-1.0
|
||||||
|
/opt/local/include
|
||||||
|
/opt/include
|
||||||
|
)
|
||||||
|
|
||||||
|
get_filename_component(LIBUSB_INCLUDE_DIR ${LIBUSB_INCLUDE_DIR} ABSOLUTE)
|
||||||
|
|
||||||
|
FIND_LIBRARY(LIBUSB_LIBRARY usb-1.0
|
||||||
|
/usr/local/lib
|
||||||
|
/usr/lib
|
||||||
|
)
|
||||||
|
|
||||||
|
IF (LIBUSB_INCLUDE_DIR)
|
||||||
|
IF (LIBUSB_LIBRARY)
|
||||||
|
SET(LIBUSB_FOUND "YES")
|
||||||
|
ENDIF (LIBUSB_LIBRARY)
|
||||||
|
ENDIF (LIBUSB_INCLUDE_DIR)
|
||||||
|
|
||||||
|
MARK_AS_ADVANCED(
|
||||||
|
LIBUSB_INCLUDE_DIR
|
||||||
|
LIBUSB_LIBRARY
|
||||||
|
LIBUSB_FOUND
|
||||||
|
)
|
34
samples/sample_c/platform/linux/common/3rdparty/FindOPUS.cmake
vendored
Normal file
34
samples/sample_c/platform/linux/common/3rdparty/FindOPUS.cmake
vendored
Normal file
@ -0,0 +1,34 @@
|
|||||||
|
#
|
||||||
|
# Find the native OPUS includes and library
|
||||||
|
#
|
||||||
|
# This module defines
|
||||||
|
# OPUS_INCLUDE_DIR, where to find opus.h
|
||||||
|
# OPUS_LIBRARY, the libraries to link against to use OPUS.
|
||||||
|
# OPUS_FOUND, If false, do not try to use OPUS.
|
||||||
|
|
||||||
|
FIND_PATH(OPUS_INCLUDE_DIR opus.h
|
||||||
|
PATHS
|
||||||
|
/usr/local/include/opus
|
||||||
|
/usr/include/opus
|
||||||
|
/opt/local/include
|
||||||
|
/opt/include
|
||||||
|
)
|
||||||
|
|
||||||
|
get_filename_component(OPUS_INCLUDE_DIR ${OPUS_INCLUDE_DIR} ABSOLUTE)
|
||||||
|
|
||||||
|
FIND_LIBRARY(OPUS_LIBRARY opus
|
||||||
|
/usr/local/lib
|
||||||
|
/usr/lib
|
||||||
|
)
|
||||||
|
|
||||||
|
IF (OPUS_INCLUDE_DIR)
|
||||||
|
IF (OPUS_LIBRARY)
|
||||||
|
SET(OPUS_FOUND "YES")
|
||||||
|
ENDIF (OPUS_LIBRARY)
|
||||||
|
ENDIF (OPUS_INCLUDE_DIR)
|
||||||
|
|
||||||
|
MARK_AS_ADVANCED(
|
||||||
|
OPUS_INCLUDE_DIR
|
||||||
|
OPUS_LIBRARY
|
||||||
|
OPUS_FOUND
|
||||||
|
)
|
@ -30,6 +30,10 @@
|
|||||||
|
|
||||||
/* Private types -------------------------------------------------------------*/
|
/* Private types -------------------------------------------------------------*/
|
||||||
|
|
||||||
|
/* Private values -------------------------------------------------------------*/
|
||||||
|
static uint32_t s_localTimeMsOffset = 0;
|
||||||
|
static uint64_t s_localTimeUsOffset = 0;
|
||||||
|
|
||||||
/* Private functions declaration ---------------------------------------------*/
|
/* Private functions declaration ---------------------------------------------*/
|
||||||
|
|
||||||
/* Exported functions definition ---------------------------------------------*/
|
/* Exported functions definition ---------------------------------------------*/
|
||||||
@ -279,6 +283,12 @@ T_DjiReturnCode Osal_GetTimeMs(uint32_t *ms)
|
|||||||
gettimeofday(&time, NULL);
|
gettimeofday(&time, NULL);
|
||||||
*ms = (time.tv_sec * 1000 + time.tv_usec / 1000);
|
*ms = (time.tv_sec * 1000 + time.tv_usec / 1000);
|
||||||
|
|
||||||
|
if (s_localTimeMsOffset == 0) {
|
||||||
|
s_localTimeMsOffset = *ms;
|
||||||
|
} else {
|
||||||
|
*ms = *ms - s_localTimeMsOffset;
|
||||||
|
}
|
||||||
|
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -289,6 +299,12 @@ T_DjiReturnCode Osal_GetTimeUs(uint64_t *us)
|
|||||||
gettimeofday(&time, NULL);
|
gettimeofday(&time, NULL);
|
||||||
*us = (time.tv_sec * 1000000 + time.tv_usec);
|
*us = (time.tv_sec * 1000000 + time.tv_usec);
|
||||||
|
|
||||||
|
if (s_localTimeUsOffset == 0) {
|
||||||
|
s_localTimeUsOffset = *us;
|
||||||
|
} else {
|
||||||
|
*us = *us - s_localTimeMsOffset;
|
||||||
|
}
|
||||||
|
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -53,7 +53,33 @@ add_executable(${PROJECT_NAME}
|
|||||||
${MODULE_SAMPLE_SRC}
|
${MODULE_SAMPLE_SRC}
|
||||||
${MODULE_COMMON_SRC}
|
${MODULE_COMMON_SRC}
|
||||||
${MODULE_HAL_SRC})
|
${MODULE_HAL_SRC})
|
||||||
target_link_libraries(${PROJECT_NAME} m usb-1.0)
|
|
||||||
|
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_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)
|
||||||
|
|
||||||
|
target_link_libraries(${PROJECT_NAME} m)
|
||||||
|
|
||||||
add_custom_command(TARGET ${PROJECT_NAME}
|
add_custom_command(TARGET ${PROJECT_NAME}
|
||||||
PRE_LINK COMMAND cmake ..
|
PRE_LINK COMMAND cmake ..
|
||||||
|
@ -162,6 +162,11 @@ int main(int argc, char **argv)
|
|||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||||
USER_LOG_ERROR("widget interaction sample init error");
|
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 {
|
} else {
|
||||||
#ifdef CONFIG_MODULE_SAMPLE_CAMERA_EMU_ON
|
#ifdef CONFIG_MODULE_SAMPLE_CAMERA_EMU_ON
|
||||||
returnCode = DjiTest_CameraEmuBaseStartService();
|
returnCode = DjiTest_CameraEmuBaseStartService();
|
||||||
@ -216,11 +221,9 @@ int main(int argc, char **argv)
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef CONFIG_MODULE_SAMPLE_WIDGET_SPEAKER_ON
|
#ifdef CONFIG_MODULE_SAMPLE_WIDGET_SPEAKER_ON
|
||||||
if (aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) {
|
returnCode = DjiTest_WidgetSpeakerStartService();
|
||||||
returnCode = DjiTest_WidgetSpeakerStartService();
|
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
USER_LOG_ERROR("widget speaker test init error");
|
||||||
USER_LOG_ERROR("widget speaker test init error");
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -32,12 +32,16 @@
|
|||||||
|
|
||||||
#define LINUX_USB_BULK_EP_OUT "/dev/usb-ffs/bulk/ep1"
|
#define LINUX_USB_BULK_EP_OUT "/dev/usb-ffs/bulk/ep1"
|
||||||
#define LINUX_USB_BULK_EP_IN "/dev/usb-ffs/bulk/ep2"
|
#define LINUX_USB_BULK_EP_IN "/dev/usb-ffs/bulk/ep2"
|
||||||
#define LINUX_USB_PID (0x0955)
|
#define LINUX_USB_PID (0x7020)
|
||||||
#define LINUX_USB_VID (0x7020)
|
#define LINUX_USB_VID (0x0955)
|
||||||
|
|
||||||
/* Private types -------------------------------------------------------------*/
|
/* Private types -------------------------------------------------------------*/
|
||||||
typedef struct {
|
typedef struct {
|
||||||
|
#ifdef LIBUSB_INSTALLED
|
||||||
libusb_device_handle *handle;
|
libusb_device_handle *handle;
|
||||||
|
#else
|
||||||
|
void *handle;
|
||||||
|
#endif
|
||||||
int32_t ep1;
|
int32_t ep1;
|
||||||
int32_t ep2;
|
int32_t ep2;
|
||||||
T_DjiHalUsbBulkInfo usbBulkInfo;
|
T_DjiHalUsbBulkInfo usbBulkInfo;
|
||||||
@ -59,6 +63,7 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (usbBulkInfo.isUsbHost == true) {
|
if (usbBulkInfo.isUsbHost == true) {
|
||||||
|
#ifdef LIBUSB_INSTALLED
|
||||||
ret = libusb_init(NULL);
|
ret = libusb_init(NULL);
|
||||||
if (ret < 0) {
|
if (ret < 0) {
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||||
@ -78,7 +83,7 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan
|
|||||||
|
|
||||||
((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle;
|
((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle;
|
||||||
memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo));
|
memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo));
|
||||||
|
#endif
|
||||||
} else {
|
} else {
|
||||||
((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle;
|
((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle;
|
||||||
memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo));
|
memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo));
|
||||||
@ -109,9 +114,11 @@ T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle)
|
|||||||
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
||||||
|
|
||||||
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
||||||
|
#ifdef LIBUSB_INSTALLED
|
||||||
libusb_release_interface(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum);
|
libusb_release_interface(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum);
|
||||||
osalHandler->TaskSleepMs(100);
|
osalHandler->TaskSleepMs(100);
|
||||||
libusb_exit(NULL);
|
libusb_exit(NULL);
|
||||||
|
#endif
|
||||||
} else {
|
} else {
|
||||||
close(((T_HalUsbBulkObj *) usbBulkHandle)->ep1);
|
close(((T_HalUsbBulkObj *) usbBulkHandle)->ep1);
|
||||||
close(((T_HalUsbBulkObj *) usbBulkHandle)->ep2);
|
close(((T_HalUsbBulkObj *) usbBulkHandle)->ep2);
|
||||||
@ -136,18 +143,21 @@ T_DjiReturnCode HalUsbBulk_WriteData(T_DjiUsbBulkHandle usbBulkHandle, const uin
|
|||||||
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
||||||
|
|
||||||
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
||||||
|
#ifdef LIBUSB_INSTALLED
|
||||||
ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointOut,
|
ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointOut,
|
||||||
(uint8_t *) buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_TIMEOUT_MS);
|
(uint8_t *) buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_TIMEOUT_MS);
|
||||||
if (ret < 0) {
|
if (ret < 0) {
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
USER_LOG_ERROR("Write usb bulk data failed, errno = %d", ret);
|
||||||
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||||
}
|
}
|
||||||
|
|
||||||
*realLen = actualLen;
|
*realLen = actualLen;
|
||||||
|
#endif
|
||||||
} else {
|
} else {
|
||||||
*realLen = write(((T_HalUsbBulkObj *) usbBulkHandle)->ep1, buf, len);
|
*realLen = write(((T_HalUsbBulkObj *) usbBulkHandle)->ep1, buf, len);
|
||||||
}
|
}
|
||||||
|
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||||
}
|
}
|
||||||
|
|
||||||
T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len,
|
T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len,
|
||||||
@ -164,13 +174,16 @@ T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *b
|
|||||||
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
||||||
|
|
||||||
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
||||||
|
#ifdef LIBUSB_INSTALLED
|
||||||
ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointIn,
|
ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointIn,
|
||||||
buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_WAIT_FOREVER);
|
buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_WAIT_FOREVER);
|
||||||
if (ret < 0) {
|
if (ret < 0) {
|
||||||
|
USER_LOG_ERROR("Read usb bulk data failed, errno = %d", ret);
|
||||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||||
}
|
}
|
||||||
|
|
||||||
*realLen = actualLen;
|
*realLen = actualLen;
|
||||||
|
#endif
|
||||||
} else {
|
} else {
|
||||||
*realLen = read(((T_HalUsbBulkObj *) usbBulkHandle)->ep2, buf, len);
|
*realLen = read(((T_HalUsbBulkObj *) usbBulkHandle)->ep2, buf, len);
|
||||||
}
|
}
|
||||||
|
@ -38,10 +38,13 @@
|
|||||||
#include <sys/socket.h>
|
#include <sys/socket.h>
|
||||||
#include <netinet/in.h>
|
#include <netinet/in.h>
|
||||||
#include <arpa/inet.h>
|
#include <arpa/inet.h>
|
||||||
#include <libusb-1.0/libusb.h>
|
|
||||||
|
|
||||||
#include "dji_platform.h"
|
#include "dji_platform.h"
|
||||||
|
|
||||||
|
#ifdef LIBUSB_INSTALLED
|
||||||
|
#include <libusb-1.0/libusb.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
extern "C" {
|
extern "C" {
|
||||||
#endif
|
#endif
|
||||||
|
@ -46,7 +46,7 @@ include_directories(../../../../../module_sample
|
|||||||
../../drivers/USB_HOST/App
|
../../drivers/USB_HOST/App
|
||||||
../../drivers/BSP
|
../../drivers/BSP
|
||||||
../../hal/
|
../../hal/
|
||||||
../../osal/
|
../../../common/osal/
|
||||||
../../middlewares/Third_Party/FreeRTOS/Source/include
|
../../middlewares/Third_Party/FreeRTOS/Source/include
|
||||||
../../middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS
|
../../middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS
|
||||||
../../middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F
|
../../middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F
|
||||||
@ -79,7 +79,7 @@ file(GLOB_RECURSE MODULE_SAMPLE_SRC
|
|||||||
)
|
)
|
||||||
|
|
||||||
file(GLOB_RECURSE SOURCES
|
file(GLOB_RECURSE SOURCES
|
||||||
"../../osal/*.*"
|
"../../../common/osal/*.*"
|
||||||
"../../drivers/BSP/*.*"
|
"../../drivers/BSP/*.*"
|
||||||
"../../hal/*.*"
|
"../../hal/*.*"
|
||||||
"../../drivers/USB_HOST/*.*"
|
"../../drivers/USB_HOST/*.*"
|
||||||
|
Reference in New Issue
Block a user