diff --git a/LICENSE.txt b/LICENSE.txt index 01ad266..76bf3d9 100644 --- a/LICENSE.txt +++ b/LICENSE.txt @@ -7,6 +7,7 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in │   │   ├── dji_sdk_template.c │   │   └── dji_sdk_template.h │   ├── reference_designs +│ │ ├── E-Port Lite Schematic Reference.pdf │   │   └── Type-C Schematic Reference.pdf │   └── simple_model │   ├── H20.stp @@ -205,6 +206,8 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in │   │   │   │   ├── util_buffer.h │   │   │   │   ├── util_file.c │   │   │   │   ├── util_file.h +│   │   │   │   ├── util_link_list.c +│   │   │   │   ├── util_link_list.h │   │   │   │   ├── util_md5.c │   │   │   │   ├── util_md5.h │   │   │   │   ├── util_misc.c @@ -327,19 +330,19 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in │   │   │   │   ├── hal_uart.h │   │   │   │   ├── hal_usb_bulk.c │   │   │   │   └── hal_usb_bulk.h -│   │   │   └── nvidia_jetson -│   │   │   ├── application -│   │   │   │   ├── dji_sdk_app_info.h -│   │   │   │   ├── dji_sdk_config.h -│   │   │   │   └── main.c -│   │   │   ├── CMakeLists.txt -│   │   │   └── hal -│   │   │   ├── hal_network.c -│   │   │   ├── hal_network.h -│   │   │   ├── hal_uart.c -│   │   │   ├── hal_uart.h -│   │   │   ├── hal_usb_bulk.c -│   │   │   └── hal_usb_bulk.h +│   │   │   ├── nvidia_jetson +│   │   │   │   ├── application +│   │   │   │   │   ├── dji_sdk_app_info.h +│   │   │   │   │   ├── dji_sdk_config.h +│   │   │   │   │   └── main.c +│   │   │   │   ├── CMakeLists.txt +│   │   │   │   └── hal +│   │   │   │   ├── hal_network.c +│   │   │   │   ├── hal_network.h +│   │   │   │   ├── hal_uart.c +│   │   │   │   ├── hal_uart.h +│   │   │   │   ├── hal_usb_bulk.c +│   │   │   │   └── hal_usb_bulk.h │   │   └── rtos_freertos │   │   ├── common │   │   │   └── osal @@ -761,21 +764,21 @@ The following portions of the DJI’s Payload SDK (“Software” referred to in │   │   ├── hal_uart.h │   │   ├── hal_usb_bulk.c │   │   └── hal_usb_bulk.h -│   └── nvidia_jetson -│   ├── application -│   │   ├── application.cpp -│   │   ├── application.hpp -│   │   ├── dji_sdk_app_info.h -│   │   ├── dji_sdk_config.h -│   │   └── main.cpp -│   ├── CMakeLists.txt -│   └── hal -│   ├── hal_network.c -│   ├── hal_network.h -│   ├── hal_uart.c -│   ├── hal_uart.h -│   ├── hal_usb_bulk.c -│   └── hal_usb_bulk.h +│   ├── nvidia_jetson +│   │   ├── application +│   │   │   ├── application.cpp +│   │   │   ├── application.hpp +│   │   │   ├── dji_sdk_app_info.h +│   │   │   ├── dji_sdk_config.h +│   │   │   └── main.cpp +│   │   ├── CMakeLists.txt +│   │   └── hal +│   │   ├── hal_network.c +│   │   ├── hal_network.h +│   │   ├── hal_uart.c +│   │   ├── hal_uart.h +│   │   ├── hal_usb_bulk.c +│   │   └── hal_usb_bulk.h └── tools └── file2c ├── file2c.exe diff --git a/README.md b/README.md index ecbe8bb..6f7ba35 100644 --- a/README.md +++ b/README.md @@ -1,7 +1,7 @@ # DJI Payload SDK (PSDK) -![](https://img.shields.io/badge/version-V3.7.0-green.svg) -![](https://img.shields.io/badge/platform-linux_|_rtos-green.svg) +![](https://img.shields.io/badge/version-V3.8.0-cyan.svg) +![](https://img.shields.io/badge/platform-linux_|_rtos-cyan.svg) ![](https://img.shields.io/badge/license-MIT-blue.svg) ## What is the DJI Payload SDK? @@ -23,22 +23,20 @@ to get the latest version information. ## Latest Release -PSDK 3.7.0 was released on 31 Oct 2023. This version of Payload SDK mainly add some new features support and fixed some +The latest release version of PSDK is 3.8.0. This version of Payload SDK mainly add some new features support and fixed some bugs. Please refer to the release notes for detailed changes list. -* Added L2 new camera model support -* Added FlyCart 30 new drone model support -* Added support for L2 subscription 3D point cloud data function -* Added L2 support for downloading original point cloud files -* Fixed the issue where M300 RTK and M350 RTK occasionally failed to negotiate load -* Fixed an issue where some open source library conflicts caused flight control module registration to fail -* Fixed the issue where PSDK obtains aircraft version numbers and displays them in reverse order -* Fixed an issue where the zoom value range of some camera zoom rings was incorrect -* Fixed the problem that the Sample value not updated when repeatedly running the M30/M3 series drone data subscription -* Fixed compatibility issues on some ESP32 platforms -* Optimize the return value prompt of MOP channel closing and destruction -* Optimize the point of interest surround function Sample log prompt -* Optimize compilation warning level +* Added support for the M3D series models +* Fixed memory leak in the HMS Sample +* Resolved compilation errors of Sample header files in certain environments +* Fixed unexpected crashes in C++ Sample when attempting to use unsupported features +* Enhanced prompts for camera Sample file downloads +* Optimized some improper uses of CMake in samples +* Change firmware version numbers in the PSDK Sample now align across DJI Assistant 2 and Pilot 2. +> Note: DJI Assistant 2 prevents firmware downgrading during payload upgrades. Ensure your upgrade package's name (the version number) is higher than the payload's reported firmware version. +> To comply with DJI Assistant 2 verification: You can simply rename your payload firmware upgrade package to make it valid, or maintain the previous practice of independently setting a version number to be checked during upgrades. +* In the STM32 FreeRTOS Sample, the heap size has been increased to 90,000 bytes. +> This may cause startup or build failures on some devices. You can adjust the stack size according to the business requirements of your hardware. ## License diff --git a/doc/reference_designs/E-Port Lite Schematic Reference.pdf b/doc/reference_designs/E-Port Lite Schematic Reference.pdf new file mode 100644 index 0000000..41ac39c Binary files /dev/null and b/doc/reference_designs/E-Port Lite Schematic Reference.pdf differ diff --git a/psdk_lib/include/dji_fc_subscription.h b/psdk_lib/include/dji_fc_subscription.h index 4ee7ac0..af8657e 100644 --- a/psdk_lib/include/dji_fc_subscription.h +++ b/psdk_lib/include/dji_fc_subscription.h @@ -779,7 +779,7 @@ typedef T_DjiVector3f T_DjiFcSubscriptionAngularRateFusioned; typedef T_DjiVector3f T_DjiFcSubscriptionAngularRateRaw; /** - * @brief DJI_FC_SUBSCRIPTION_TOPIC_ALTITUDE_FUSED topic data structure. + * @brief DJI_FC_SUBSCRIPTION_TOPIC_ANGULAR_RATE_RAW topic data structure. */ typedef dji_f32_t T_DjiFcSubscriptionAltitudeFused; diff --git a/psdk_lib/include/dji_liveview.h b/psdk_lib/include/dji_liveview.h index e537793..a141463 100644 --- a/psdk_lib/include/dji_liveview.h +++ b/psdk_lib/include/dji_liveview.h @@ -68,6 +68,9 @@ typedef enum { DJI_LIVEVIEW_CAMERA_SOURCE_M3E_VIS = 1, DJI_LIVEVIEW_CAMERA_SOURCE_M3T_VIS = 1, DJI_LIVEVIEW_CAMERA_SOURCE_M3T_IR = 2, + DJI_LIVEVIEW_CAMERA_SOURCE_M3D_VIS = 1, + DJI_LIVEVIEW_CAMERA_SOURCE_M3TD_VIS = 1, + DJI_LIVEVIEW_CAMERA_SOURCE_M3TD_IR = 2, } E_DjiLiveViewCameraSource; /** diff --git a/psdk_lib/include/dji_typedef.h b/psdk_lib/include/dji_typedef.h index c60b878..1ac5767 100644 --- a/psdk_lib/include/dji_typedef.h +++ b/psdk_lib/include/dji_typedef.h @@ -76,7 +76,7 @@ typedef enum { DJI_MOUNT_POSITION_TYPE_UNKNOWN = 0, DJI_MOUNT_POSITION_TYPE_PAYLOAD_PORT = 1, DJI_MOUNT_POSITION_TYPE_EXTENSION_PORT = 2, - DJI_MOUNT_POSITION_TYPE_EXTENSION_LITE_PORT = 3, + DJI_MOUNT_POSITION_TYPE_EXTENSION_LITE_PORT = 3 } E_DjiMountPositionType; typedef enum { @@ -95,6 +95,7 @@ typedef enum { DJI_AIRCRAFT_SERIES_M30 = 3, DJI_AIRCRAFT_SERIES_M3 = 4, DJI_AIRCRAFT_SERIES_M350 = 5, + DJI_AIRCRAFT_SERIES_M3D = 6, DJI_AIRCRAFT_SERIES_FC30 = 7, } E_DjiAircraftSeries; @@ -110,6 +111,8 @@ typedef enum { DJI_AIRCRAFT_TYPE_FC30 = 78, /* ! */ DJI_AIRCRAFT_TYPE_M3T = 79, /*!< Aircraft type is Mavic 3T. */ DJI_AIRCRAFT_TYPE_M350_RTK = 89, /*!< Aircraft type is Matrice 350 RTK. */ + DJI_AIRCRAFT_TYPE_M3D = 91, /*!< Aircraft type is Matrice 3D. */ + DJI_AIRCRAFT_TYPE_M3TD = 93, /*!< Aircraft type is Matrice 3TD. */ } E_DjiAircraftType; /** @@ -131,6 +134,8 @@ typedef enum { DJI_CAMERA_TYPE_M30T, /*!< Camera type is M30T. */ DJI_CAMERA_TYPE_M3E, /*!< Camera type is M3E. */ DJI_CAMERA_TYPE_M3T, /*!< Camera type is M3T. */ + DJI_CAMERA_TYPE_M3D, /*!< Camera type is Matrice 3D. */ + DJI_CAMERA_TYPE_M3TD, /*!< Camera type is Matrice 3TD. */ } E_DjiCameraType; /** diff --git a/psdk_lib/include/dji_version.h b/psdk_lib/include/dji_version.h index a942a5b..0c46a6c 100644 --- a/psdk_lib/include/dji_version.h +++ b/psdk_lib/include/dji_version.h @@ -34,10 +34,10 @@ extern "C" { /* 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_MINOR 7 /*!< DJI SDK minor version num, when add functionality in a backwards compatible manner changes. Range from 0 to 99. */ +#define DJI_VERSION_MINOR 8 /*!< 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_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 1906 /*!< DJI SDK version build info, when jenkins trigger build changes. Range from 0 to 65535. */ +#define DJI_VERSION_BUILD 1929 /*!< DJI SDK version build info, when jenkins trigger build changes. Range from 0 to 65535. */ /* Exported types ------------------------------------------------------------*/ diff --git a/psdk_lib/lib/aarch64-himix100-linux-gcc/libpayloadsdk.a b/psdk_lib/lib/aarch64-himix100-linux-gcc/libpayloadsdk.a index 7e98b53..ba37e56 100644 Binary files a/psdk_lib/lib/aarch64-himix100-linux-gcc/libpayloadsdk.a and b/psdk_lib/lib/aarch64-himix100-linux-gcc/libpayloadsdk.a differ diff --git a/psdk_lib/lib/aarch64-linux-android-gcc/libpayloadsdk.a b/psdk_lib/lib/aarch64-linux-android-gcc/libpayloadsdk.a index c5567d3..1caf001 100644 Binary files a/psdk_lib/lib/aarch64-linux-android-gcc/libpayloadsdk.a and b/psdk_lib/lib/aarch64-linux-android-gcc/libpayloadsdk.a differ diff --git a/psdk_lib/lib/aarch64-linux-gnu-gcc/libpayloadsdk.a b/psdk_lib/lib/aarch64-linux-gnu-gcc/libpayloadsdk.a index 7329c85..129e0b6 100644 Binary files a/psdk_lib/lib/aarch64-linux-gnu-gcc/libpayloadsdk.a and b/psdk_lib/lib/aarch64-linux-gnu-gcc/libpayloadsdk.a differ diff --git a/psdk_lib/lib/arm-himix100-linux-gcc/libpayloadsdk.a b/psdk_lib/lib/arm-himix100-linux-gcc/libpayloadsdk.a index b61f621..61ea040 100644 Binary files a/psdk_lib/lib/arm-himix100-linux-gcc/libpayloadsdk.a and b/psdk_lib/lib/arm-himix100-linux-gcc/libpayloadsdk.a differ diff --git a/psdk_lib/lib/arm-himix200-linux-gcc/libpayloadsdk.a b/psdk_lib/lib/arm-himix200-linux-gcc/libpayloadsdk.a index 7f33c52..4a322c9 100644 Binary files a/psdk_lib/lib/arm-himix200-linux-gcc/libpayloadsdk.a and b/psdk_lib/lib/arm-himix200-linux-gcc/libpayloadsdk.a differ diff --git a/psdk_lib/lib/arm-hisiv300-linux-gcc/libpayloadsdk.a b/psdk_lib/lib/arm-hisiv300-linux-gcc/libpayloadsdk.a index 4da76e3..c234fbc 100644 Binary files a/psdk_lib/lib/arm-hisiv300-linux-gcc/libpayloadsdk.a and b/psdk_lib/lib/arm-hisiv300-linux-gcc/libpayloadsdk.a differ diff --git a/psdk_lib/lib/arm-hisiv400-linux-gcc/libpayloadsdk.a b/psdk_lib/lib/arm-hisiv400-linux-gcc/libpayloadsdk.a index 74ce73a..712e034 100644 Binary files a/psdk_lib/lib/arm-hisiv400-linux-gcc/libpayloadsdk.a and b/psdk_lib/lib/arm-hisiv400-linux-gcc/libpayloadsdk.a differ diff --git a/psdk_lib/lib/arm-hisiv500-linux-gcc/libpayloadsdk.a b/psdk_lib/lib/arm-hisiv500-linux-gcc/libpayloadsdk.a new file mode 100644 index 0000000..f7beab3 Binary files /dev/null and b/psdk_lib/lib/arm-hisiv500-linux-gcc/libpayloadsdk.a differ diff --git a/psdk_lib/lib/arm-hisiv600-linux-gcc/libpayloadsdk.a b/psdk_lib/lib/arm-hisiv600-linux-gcc/libpayloadsdk.a index 115546d..32e241f 100644 Binary files a/psdk_lib/lib/arm-hisiv600-linux-gcc/libpayloadsdk.a and b/psdk_lib/lib/arm-hisiv600-linux-gcc/libpayloadsdk.a differ diff --git a/psdk_lib/lib/arm-linux-androideabi-gcc/libpayloadsdk.a b/psdk_lib/lib/arm-linux-androideabi-gcc/libpayloadsdk.a index b769fd7..3f13e9e 100644 Binary files a/psdk_lib/lib/arm-linux-androideabi-gcc/libpayloadsdk.a and b/psdk_lib/lib/arm-linux-androideabi-gcc/libpayloadsdk.a differ diff --git a/psdk_lib/lib/arm-linux-gnueabi-gcc/libpayloadsdk.a b/psdk_lib/lib/arm-linux-gnueabi-gcc/libpayloadsdk.a index ac3f82b..ea9bbbb 100644 Binary files a/psdk_lib/lib/arm-linux-gnueabi-gcc/libpayloadsdk.a and b/psdk_lib/lib/arm-linux-gnueabi-gcc/libpayloadsdk.a differ diff --git a/psdk_lib/lib/arm-linux-gnueabihf-gcc/libpayloadsdk.a b/psdk_lib/lib/arm-linux-gnueabihf-gcc/libpayloadsdk.a index ec805fe..7442c6b 100644 Binary files a/psdk_lib/lib/arm-linux-gnueabihf-gcc/libpayloadsdk.a and b/psdk_lib/lib/arm-linux-gnueabihf-gcc/libpayloadsdk.a differ diff --git a/psdk_lib/lib/arm-none-eabi-gcc/libpayloadsdk.a b/psdk_lib/lib/arm-none-eabi-gcc/libpayloadsdk.a index f1d9934..72a6244 100644 Binary files a/psdk_lib/lib/arm-none-eabi-gcc/libpayloadsdk.a and b/psdk_lib/lib/arm-none-eabi-gcc/libpayloadsdk.a differ diff --git a/psdk_lib/lib/armcc_cortex-m4/libpayload.lib b/psdk_lib/lib/armcc_cortex-m4/libpayload.lib index d8992ff..b562105 100644 Binary files a/psdk_lib/lib/armcc_cortex-m4/libpayload.lib and b/psdk_lib/lib/armcc_cortex-m4/libpayload.lib differ diff --git a/psdk_lib/lib/x86_64-linux-gnu-gcc/libpayloadsdk.a b/psdk_lib/lib/x86_64-linux-gnu-gcc/libpayloadsdk.a index 4d0f98c..cfdd6d7 100644 Binary files a/psdk_lib/lib/x86_64-linux-gnu-gcc/libpayloadsdk.a and b/psdk_lib/lib/x86_64-linux-gnu-gcc/libpayloadsdk.a differ diff --git a/psdk_lib/lib/xtensa-esp32-elf-gcc/libpayloadsdk.a b/psdk_lib/lib/xtensa-esp32-elf-gcc/libpayloadsdk.a index 3464899..4d82434 100644 Binary files a/psdk_lib/lib/xtensa-esp32-elf-gcc/libpayloadsdk.a and b/psdk_lib/lib/xtensa-esp32-elf-gcc/libpayloadsdk.a differ diff --git a/samples/sample_c++/module_sample/flight_controller/test_flight_controller_command_flying.cpp b/samples/sample_c++/module_sample/flight_controller/test_flight_controller_command_flying.cpp index f3eba49..e8916be 100644 --- a/samples/sample_c++/module_sample/flight_controller/test_flight_controller_command_flying.cpp +++ b/samples/sample_c++/module_sample/flight_controller/test_flight_controller_command_flying.cpp @@ -444,63 +444,63 @@ static void DjiUser_ShowFlightStatusByOpenCV(void) } // Display latest flight status - cv::putText(img, "Status: ", cvPoint(30, 20), FONT_HERSHEY_SIMPLEX, 0.6, + cv::putText(img, "Status: ", cv::Point(30, 20), FONT_HERSHEY_SIMPLEX, 0.6, cv::Scalar(255, 0, 0)); - cv::putText(img, "Roll: " + cv::format("%.4f", aircraftAngles.y), cvPoint(50, 50), FONT_HERSHEY_SIMPLEX, 0.5, + cv::putText(img, "Roll: " + cv::format("%.4f", aircraftAngles.y), cv::Point(50, 50), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "Pitch: " + cv::format("%.4f", aircraftAngles.x), cvPoint(50, 80), FONT_HERSHEY_SIMPLEX, 0.5, + cv::putText(img, "Pitch: " + cv::format("%.4f", aircraftAngles.x), cv::Point(50, 80), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "Yaw: " + cv::format("%.4f", aircraftAngles.z), cvPoint(50, 110), FONT_HERSHEY_SIMPLEX, 0.5, + cv::putText(img, "Yaw: " + cv::format("%.4f", aircraftAngles.z), cv::Point(50, 110), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "WorldX: " + cv::format("%.4f", positionVo.x), cvPoint(50, 140), FONT_HERSHEY_SIMPLEX, 0.5, + cv::putText(img, "WorldX: " + cv::format("%.4f", positionVo.x), cv::Point(50, 140), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "WorldY: " + cv::format("%.4f", positionVo.y), cvPoint(50, 170), FONT_HERSHEY_SIMPLEX, 0.5, + cv::putText(img, "WorldY: " + cv::format("%.4f", positionVo.y), cv::Point(50, 170), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "WorldZ: " + cv::format("%.4f", altitudeOfHomePoint), cvPoint(50, 200), FONT_HERSHEY_SIMPLEX, + cv::putText(img, "WorldZ: " + cv::format("%.4f", altitudeOfHomePoint), cv::Point(50, 200), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "Latitude: " + cv::format("%.4f", (dji_f64_t) s_gpsPosition.y / 10000000), cvPoint(50, 230), + cv::putText(img, "Latitude: " + cv::format("%.4f", (dji_f64_t) s_gpsPosition.y / 10000000), cv::Point(50, 230), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "Longitude: " + cv::format("%.4f", (dji_f64_t) s_gpsPosition.x / 10000000), cvPoint(50, 260), + cv::putText(img, "Longitude: " + cv::format("%.4f", (dji_f64_t) s_gpsPosition.x / 10000000), cv::Point(50, 260), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "Battery1: " + cv::format("%d%%", singleBatteryInfo1.batteryCapacityPercent), cvPoint(50, 290), + cv::putText(img, "Battery1: " + cv::format("%d%%", singleBatteryInfo1.batteryCapacityPercent), cv::Point(50, 290), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "Battery2: " + cv::format("%d%%", singleBatteryInfo2.batteryCapacityPercent), cvPoint(50, 320), + cv::putText(img, "Battery2: " + cv::format("%d%%", singleBatteryInfo2.batteryCapacityPercent), cv::Point(50, 320), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "Config: ", cvPoint(300, 20), FONT_HERSHEY_SIMPLEX, 0.6, + cv::putText(img, "Config: ", cv::Point(300, 20), FONT_HERSHEY_SIMPLEX, 0.6, cv::Scalar(255, 0, 0)); cv::putText(img, "-> RcLostAction(Sync APP): " + cv::format("%d (0-hover 1-landing 2-gohome)", rcLostAction), - cvPoint(320, 50), + cv::Point(320, 50), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "-> GoHomeAltitude(Sync APP): " + cv::format("%d", s_goHomeAltitude), cvPoint(320, 80), + cv::putText(img, "-> GoHomeAltitude(Sync APP): " + cv::format("%d", s_goHomeAltitude), cv::Point(320, 80), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "-> RTK-Enable(Sync APP): " + cv::format("%d", rtkPositionEnableStatus), cvPoint(320, 110), + cv::putText(img, "-> RTK-Enable(Sync APP): " + cv::format("%d", rtkPositionEnableStatus), cv::Point(320, 110), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "-> HomePointLatitude: " + cv::format("%.4f", s_homeLocation.latitude), cvPoint(320, 140), + cv::putText(img, "-> HomePointLatitude: " + cv::format("%.4f", s_homeLocation.latitude), cv::Point(320, 140), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "-> HomePointLongitude: " + cv::format("%.4f", s_homeLocation.longitude), cvPoint(320, 170), + cv::putText(img, "-> HomePointLongitude: " + cv::format("%.4f", s_homeLocation.longitude), cv::Point(320, 170), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "-> FlyingSpeed: " + cv::format("%.2f", s_flyingSpeed), cvPoint(320, 200), + cv::putText(img, "-> FlyingSpeed: " + cv::format("%.2f", s_flyingSpeed), cv::Point(320, 200), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "-> downwardsVisEnable(Sync APP): " + cv::format("%d", downwardsVisEnable), cvPoint(320, 230), + cv::putText(img, "-> downwardsVisEnable(Sync APP): " + cv::format("%d", downwardsVisEnable), cv::Point(320, 230), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "-> upwardsVisEnable(Sync APP): " + cv::format("%d", upwardsVisEnable), cvPoint(320, 260), + cv::putText(img, "-> upwardsVisEnable(Sync APP): " + cv::format("%d", upwardsVisEnable), cv::Point(320, 260), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "-> horizontalVisEnable(Sync APP): " + cv::format("%d", horizontalVisEnable), cvPoint(320, 290), + cv::putText(img, "-> horizontalVisEnable(Sync APP): " + cv::format("%d", horizontalVisEnable), cv::Point(320, 290), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); - cv::putText(img, "-> ControlDevice: " + cv::format("%d", controlDevice.deviceStatus), cvPoint(320, 320), + cv::putText(img, "-> ControlDevice: " + cv::format("%d", controlDevice.deviceStatus), cv::Point(320, 320), FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(200, 0, 0)); cv::putText(img, "[Q]-Up [W]-Front [E]-Down [R]-TakeOff [T]-CancelLanding [Y]-CancelGoHome [I]-ArrestFly [O]-CancelArrestFly [P]-EmgStopMotor", - cvPoint(30, 400), FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(128, 0, 0)); + cv::Point(30, 400), FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(128, 0, 0)); cv::putText(img, "[A]-Left [S]-Near [D]-Right [F]-ForceLand [G]-Landing [H]-GoHome [J]-UpdateConfig [K]-Brake [L]-CancelBrakeI", - cvPoint(30, 430), FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(128, 0, 0)); + cv::Point(30, 430), FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(128, 0, 0)); cv::putText(img, "[Z]-Yaw- [X]-RefreshHomePoint [C]-Yaw+ [V]-ConfirmLanding [B]-TurnOn [N]-TurnOff [M]-ObtainCtrlAuth", - cvPoint(30, 460), FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(128, 0, 0)); + cv::Point(30, 460), FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(128, 0, 0)); cv::imshow("Payload SDK Command Flying Data Observation Window", img); cv::waitKey(1); diff --git a/samples/sample_c++/module_sample/gimbal/test_gimbal_entry.cpp b/samples/sample_c++/module_sample/gimbal/test_gimbal_entry.cpp index 7e13bc3..6d670f3 100644 --- a/samples/sample_c++/module_sample/gimbal/test_gimbal_entry.cpp +++ b/samples/sample_c++/module_sample/gimbal/test_gimbal_entry.cpp @@ -286,7 +286,8 @@ start: } USER_LOG_INFO("Subscribe topic DJI_FC_SUBSCRIPTION_TOPIC_THREE_GIMBAL_DATA succefully."); } - else if (aircraftSeries == DJI_AIRCRAFT_SERIES_M30 || aircraftSeries == DJI_AIRCRAFT_SERIES_M3) { + else if (aircraftSeries == DJI_AIRCRAFT_SERIES_M30 || aircraftSeries == DJI_AIRCRAFT_SERIES_M3 || + aircraftSeries == DJI_AIRCRAFT_SERIES_M3D) { returnCode = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, DJI_DATA_SUBSCRIPTION_TOPIC_50_HZ, NULL); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("DjiFcSubscription_SubscribeTopic %d return %d", DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, returnCode); @@ -401,7 +402,8 @@ start: threeGimbalData.anglesData[gimbalMountPosition - 1].roll, threeGimbalData.anglesData[gimbalMountPosition - 1].yaw); } - else if (aircraftSeries == DJI_AIRCRAFT_SERIES_M30 || aircraftSeries == DJI_AIRCRAFT_SERIES_M3) { + else if (aircraftSeries == DJI_AIRCRAFT_SERIES_M30 || aircraftSeries == DJI_AIRCRAFT_SERIES_M3 || + aircraftSeries == DJI_AIRCRAFT_SERIES_M3D) { returnCode = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, (uint8_t *) &gimbalAngles, sizeof(T_DjiFcSubscriptionGimbalAngles), diff --git a/samples/sample_c++/module_sample/liveview/test_liveview.cpp b/samples/sample_c++/module_sample/liveview/test_liveview.cpp index 91ee7f7..e3e3ada 100644 --- a/samples/sample_c++/module_sample/liveview/test_liveview.cpp +++ b/samples/sample_c++/module_sample/liveview/test_liveview.cpp @@ -42,7 +42,7 @@ LiveviewSample::LiveviewSample() returnCode = DjiLiveview_Init(); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { - perror("Liveview init failed"); + throw ("Liveview init failed"); } streamDecoder = { diff --git a/samples/sample_c++/module_sample/liveview/test_liveview_entry.cpp b/samples/sample_c++/module_sample/liveview/test_liveview_entry.cpp index 2d9dda9..1f2b675 100755 --- a/samples/sample_c++/module_sample/liveview/test_liveview_entry.cpp +++ b/samples/sample_c++/module_sample/liveview/test_liveview_entry.cpp @@ -82,9 +82,15 @@ void DjiUser_RunCameraStreamViewSample() char mainName[] = "MAIN_CAM"; char viceName[] = "VICE_CAM"; char topName[] = "TOP_CAM"; - auto *liveviewSample = new LiveviewSample(); T_DjiReturnCode returnCode; + LiveviewSample *liveviewSample; + try { + liveviewSample = new LiveviewSample(); + } catch (...) { + return; + } + returnCode = DjiUser_GetCurrentFileDirPath(__FILE__, DJI_FILE_PATH_SIZE_MAX, curFileDirPath); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("Get file current path error, stat = 0x%08llX", returnCode); diff --git a/samples/sample_c++/module_sample/perception/test_perception.cpp b/samples/sample_c++/module_sample/perception/test_perception.cpp index 96b222e..a48c8fd 100644 --- a/samples/sample_c++/module_sample/perception/test_perception.cpp +++ b/samples/sample_c++/module_sample/perception/test_perception.cpp @@ -46,7 +46,7 @@ PerceptionSample::PerceptionSample() USER_LOG_ERROR("Perception feature will support on later version."); } - perror("Perception init failed"); + throw ("Perception init failed"); } } diff --git a/samples/sample_c++/module_sample/perception/test_perception_entry.cpp b/samples/sample_c++/module_sample/perception/test_perception_entry.cpp index b297668..9b23f74 100644 --- a/samples/sample_c++/module_sample/perception/test_perception_entry.cpp +++ b/samples/sample_c++/module_sample/perception/test_perception_entry.cpp @@ -103,10 +103,16 @@ void DjiUser_RunStereoVisionViewSample(void) T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); char inputChar; char isQuit; - auto *perceptionSample = new PerceptionSample; T_DjiReturnCode returnCode; T_DjiPerceptionCameraParametersPacket cameraParametersPacket = {0}; + PerceptionSample *perceptionSample; + try { + perceptionSample = new PerceptionSample; + } catch (...) { + return; + } + returnCode = osalHandler->MutexCreate(&s_stereoImagePacket.mutex); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("Crete mutex failed, return code:0x%08X", returnCode); diff --git a/samples/sample_c++/platform/linux/common/3rdparty/FindFFMPEG.cmake b/samples/sample_c++/platform/linux/common/3rdparty/FindFFMPEG.cmake index 3b47063..81ca8d0 100644 --- a/samples/sample_c++/platform/linux/common/3rdparty/FindFFMPEG.cmake +++ b/samples/sample_c++/platform/linux/common/3rdparty/FindFFMPEG.cmake @@ -111,11 +111,6 @@ FIND_LIBRARY(FFMPEG_z_LIBRARY z /usr/lib ) -FIND_LIBRARY(FFMPEG_swresample_LIBRARY swresample - /usr/local/lib - /usr/lib -) - SET(FFMPEG_LIBRARIES) IF(FFMPEG_INCLUDE_DIR) IF(FFMPEG_avformat_LIBRARY) @@ -125,8 +120,7 @@ IF(FFMPEG_INCLUDE_DIR) SET( FFMPEG_BASIC_LIBRARIES ${FFMPEG_avcodec_LIBRARY} ${FFMPEG_avformat_LIBRARY} - ${FFMPEG_avutil_LIBRARY} - ${FFMPEG_swresample_LIBRARY} + ${FFMPEG_avutil_LIBRARY} ) # swscale is always a part of newer ffmpeg distros @@ -184,5 +178,4 @@ MARK_AS_ADVANCED( FFMPEG_gsm_LIBRARY FFMPEG_swscale_LIBRARY FFMPEG_z_LIBRARY - FFMPEG_swresample_LIBRARY ) diff --git a/samples/sample_c++/platform/linux/manifold2/CMakeLists.txt b/samples/sample_c++/platform/linux/manifold2/CMakeLists.txt index 3720e43..76878d5 100644 --- a/samples/sample_c++/platform/linux/manifold2/CMakeLists.txt +++ b/samples/sample_c++/platform/linux/manifold2/CMakeLists.txt @@ -71,8 +71,7 @@ if (OpenCV_FOUND) message(STATUS " - Includes: ${OpenCV_INCLUDE_DIRS}") message(STATUS " - Libraries: ${OpenCV_LIBRARIES}") add_definitions(-DOPEN_CV_INSTALLED) - execute_process(COMMAND opencv_version OUTPUT_VARIABLE OPENCV_VERSION) - if (${OPENCV_VERSION} STRLESS "4.0.0") + if ("${OpenCV_VERSION}" STRLESS "4.0.0") add_definitions(-DOPEN_CV_VERSION_3) else () diff --git a/samples/sample_c++/platform/linux/nvidia_jetson/CMakeLists.txt b/samples/sample_c++/platform/linux/nvidia_jetson/CMakeLists.txt index c1c0814..4eff6da 100644 --- a/samples/sample_c++/platform/linux/nvidia_jetson/CMakeLists.txt +++ b/samples/sample_c++/platform/linux/nvidia_jetson/CMakeLists.txt @@ -54,8 +54,7 @@ if (OpenCV_FOUND) message(STATUS " - Includes: ${OpenCV_INCLUDE_DIRS}") message(STATUS " - Libraries: ${OpenCV_LIBRARIES}") add_definitions(-DOPEN_CV_INSTALLED) - execute_process(COMMAND opencv_version OUTPUT_VARIABLE OPENCV_VERSION) - if (${OPENCV_VERSION} STRLESS "4.0.0") + if ("${OpenCV_VERSION}" STRLESS "4.0.0") add_definitions(-DOPEN_CV_VERSION_3) else () diff --git a/samples/sample_c/module_sample/camera_emu/test_payload_cam_emu_media.c b/samples/sample_c/module_sample/camera_emu/test_payload_cam_emu_media.c index c15faf2..45a871d 100644 --- a/samples/sample_c/module_sample/camera_emu/test_payload_cam_emu_media.c +++ b/samples/sample_c/module_sample/camera_emu/test_payload_cam_emu_media.c @@ -1167,7 +1167,7 @@ static void *UserCameraMedia_SendVideoTask(void *arg) int lengthOfDataHaveBeenSent = 0; char *dataBuffer = NULL; T_TestPayloadCameraPlaybackCommand playbackCommand = {0}; - uint16_t bufferReadSize = 0; + uint16_t bufferReadSize = 0; char *videoFilePath = NULL; char *transcodedFilePath = NULL; float frameRate = 1.0f; diff --git a/samples/sample_c/module_sample/camera_manager/test_camera_manager.c b/samples/sample_c/module_sample/camera_manager/test_camera_manager.c index dd6b4b7..b33a9ff 100644 --- a/samples/sample_c/module_sample/camera_manager/test_camera_manager.c +++ b/samples/sample_c/module_sample/camera_manager/test_camera_manager.c @@ -69,6 +69,8 @@ static const T_DjiTestCameraTypeStr s_cameraTypeStrList[] = { {DJI_CAMERA_TYPE_M30T, "M30T Camera"}, {DJI_CAMERA_TYPE_M3E, "M3E Camera"}, {DJI_CAMERA_TYPE_M3T, "M3T Camera"}, + {DJI_CAMERA_TYPE_M3D, "M3D Camera"}, + {DJI_CAMERA_TYPE_M3TD, "M3TD Camera"}, }; static FILE *s_downloadMediaFile = NULL; @@ -918,8 +920,8 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition, if (cameraType == DJI_CAMERA_TYPE_H20 || cameraType == DJI_CAMERA_TYPE_H20T || cameraType == DJI_CAMERA_TYPE_H20N || cameraType == DJI_CAMERA_TYPE_M30 || cameraType == DJI_CAMERA_TYPE_M30T || cameraType == DJI_CAMERA_TYPE_M3E || - cameraType == DJI_CAMERA_TYPE_M3T || cameraType == DJI_CAMERA_TYPE_M3T || - cameraType == DJI_CAMERA_TYPE_L2) { + cameraType == DJI_CAMERA_TYPE_M3T || cameraType == DJI_CAMERA_TYPE_M3D || + cameraType == DJI_CAMERA_TYPE_M3TD) { USER_LOG_INFO("Set mounted position %d camera's exposure mode to manual mode.", mountPosition); returnCode = DjiTest_CameraManagerSetExposureMode(mountPosition, @@ -958,7 +960,8 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition, if (cameraType == DJI_CAMERA_TYPE_H20 || cameraType == DJI_CAMERA_TYPE_H20N || cameraType == DJI_CAMERA_TYPE_H20T || cameraType == DJI_CAMERA_TYPE_M30 || cameraType == DJI_CAMERA_TYPE_M30T || cameraType == DJI_CAMERA_TYPE_M3E - || cameraType == DJI_CAMERA_TYPE_M3T || cameraType == DJI_CAMERA_TYPE_L2) { + || cameraType == DJI_CAMERA_TYPE_M3T || cameraType == DJI_CAMERA_TYPE_M3D + || cameraType == DJI_CAMERA_TYPE_M3TD) { USER_LOG_INFO("Set mounted position %d camera's exposure mode to manual mode.", mountPosition); returnCode = DjiTest_CameraManagerSetExposureMode(mountPosition, @@ -1265,7 +1268,8 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition, if (cameraType == DJI_CAMERA_TYPE_XT2 || cameraType == DJI_CAMERA_TYPE_XTS || cameraType == DJI_CAMERA_TYPE_H20 || cameraType == DJI_CAMERA_TYPE_P1 || cameraType == DJI_CAMERA_TYPE_L1 || cameraType == DJI_CAMERA_TYPE_L2 || - cameraType == DJI_CAMERA_TYPE_M3E || cameraType == DJI_CAMERA_TYPE_M3T) { + cameraType == DJI_CAMERA_TYPE_M3E || cameraType == DJI_CAMERA_TYPE_M3T || + cameraType == DJI_CAMERA_TYPE_M3D || cameraType == DJI_CAMERA_TYPE_M3TD) { USER_LOG_INFO("Camera type %s does not support night scene mode!", s_cameraTypeStrList[DjiTest_CameraManagerGetCameraTypeIndex(cameraType)].cameraTypeStr); goto exitCameraModule; @@ -1368,7 +1372,7 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition, if (cameraType == DJI_CAMERA_TYPE_Z30 || cameraType == DJI_CAMERA_TYPE_XT2 || cameraType == DJI_CAMERA_TYPE_XTS || cameraType == DJI_CAMERA_TYPE_P1 || - cameraType == DJI_CAMERA_TYPE_L1) { + cameraType == DJI_CAMERA_TYPE_L1 || cameraType == DJI_CAMERA_TYPE_M3D) { USER_LOG_INFO("Camera type %s does not support set capture or recording stream(s) to storage.", s_cameraTypeStrList[DjiTest_CameraManagerGetCameraTypeIndex(cameraType)].cameraTypeStr); goto exitCameraModule; @@ -1483,6 +1487,12 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition, case E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOW_STORAGE_INFO: { T_DjiCameraManagerStorageInfo storageInfo; + if (cameraType == DJI_CAMERA_TYPE_L1 || cameraType == DJI_CAMERA_TYPE_P1 || + cameraType == DJI_CAMERA_TYPE_M3D || cameraType == DJI_CAMERA_TYPE_M3TD) { + USER_LOG_INFO("Position %d, camera type %d, doesn't support get storage info. Sample exits."); + goto exitCameraModule; + } + for (uint32_t i = 0; i < 30; i++) { returnCode = DjiCameraManager_GetStorageInfo(mountPosition, &storageInfo); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { @@ -1996,7 +2006,7 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition, if (cameraType == DJI_CAMERA_TYPE_Z30 || cameraType == DJI_CAMERA_TYPE_XT2 || cameraType == DJI_CAMERA_TYPE_H20 || cameraType == DJI_CAMERA_TYPE_P1 || cameraType == DJI_CAMERA_TYPE_L1 || cameraType == DJI_CAMERA_TYPE_M30 || - cameraType == DJI_CAMERA_TYPE_M3E || + cameraType == DJI_CAMERA_TYPE_M3E || cameraType == DJI_CAMERA_TYPE_M3D || cameraType == DJI_CAMERA_TYPE_L2) { USER_LOG_WARN("Camera type %s don't support FFC function.", s_cameraTypeStrList[DjiTest_CameraManagerGetCameraTypeIndex(cameraType)].cameraTypeStr); @@ -2042,7 +2052,7 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition, if (cameraType == DJI_CAMERA_TYPE_Z30 || cameraType == DJI_CAMERA_TYPE_XT2 || cameraType == DJI_CAMERA_TYPE_H20 || cameraType == DJI_CAMERA_TYPE_P1 || cameraType == DJI_CAMERA_TYPE_L1 || cameraType == DJI_CAMERA_TYPE_M30 || - cameraType == DJI_CAMERA_TYPE_M3E || + cameraType == DJI_CAMERA_TYPE_M3E || cameraType == DJI_CAMERA_TYPE_M3D || cameraType == DJI_CAMERA_TYPE_L2) { USER_LOG_WARN("Camera type %s don't support infrared function.", s_cameraTypeStrList[DjiTest_CameraManagerGetCameraTypeIndex(cameraType)].cameraTypeStr); @@ -2092,7 +2102,8 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition, uint16_t recordingTime; uint8_t remainingTime; - if (cameraType == DJI_CAMERA_TYPE_L1 || cameraType == DJI_CAMERA_TYPE_P1) { + if (cameraType == DJI_CAMERA_TYPE_L1 || cameraType == DJI_CAMERA_TYPE_P1 || + cameraType == DJI_CAMERA_TYPE_M3D || cameraType == DJI_CAMERA_TYPE_M3TD) { USER_LOG_INFO("Camera type %d does not support to get camera stauts such as " "capturing state, recording state.", cameraType); goto exitCameraModule; diff --git a/samples/sample_c/module_sample/flight_control/test_flight_control.c b/samples/sample_c/module_sample/flight_control/test_flight_control.c index 2d09b93..a7d1dfe 100644 --- a/samples/sample_c/module_sample/flight_control/test_flight_control.c +++ b/samples/sample_c/module_sample/flight_control/test_flight_control.c @@ -1253,7 +1253,9 @@ bool DjiTest_FlightControlGoHomeAndConfirmLanding(void) T_DjiFcSubscriptionHeightFusion heightFusion = DjiTest_FlightControlGetValueOfHeightFusion(); s_osalHandler->TaskSleepMs(1000); if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3E || - aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3T) { + aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3T || + aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3D || + aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3TD) { if ((dji_f64_t) 0.45 < heightFusion && heightFusion < (dji_f64_t) 0.55) { break; } diff --git a/samples/sample_c/module_sample/gimbal_manager/test_gimbal_manager.c b/samples/sample_c/module_sample/gimbal_manager/test_gimbal_manager.c index 25b7a4b..40cf302 100644 --- a/samples/sample_c/module_sample/gimbal_manager/test_gimbal_manager.c +++ b/samples/sample_c/module_sample/gimbal_manager/test_gimbal_manager.c @@ -140,7 +140,8 @@ T_DjiReturnCode DjiTest_GimbalManagerRunSample(E_DjiMountPosition mountPosition, rotation = s_rotationActionList[i].rotation; - if (aircraftSeries == DJI_AIRCRAFT_SERIES_M3 || aircraftSeries == DJI_AIRCRAFT_SERIES_M30) { + if (aircraftSeries == DJI_AIRCRAFT_SERIES_M3 || aircraftSeries == DJI_AIRCRAFT_SERIES_M30 + || aircraftSeries == DJI_AIRCRAFT_SERIES_M3D) { if (s_rotationActionList[i].rotation.rotationMode == DJI_GIMBAL_ROTATION_MODE_ABSOLUTE_ANGLE) { T_DjiFcSubscriptionGimbalAngles gimbalAngles = {0}; T_DjiDataTimestamp timestamp = {0}; diff --git a/samples/sample_c/module_sample/hms/test_hms.c b/samples/sample_c/module_sample/hms/test_hms.c index 7acf354..9aca37d 100644 --- a/samples/sample_c/module_sample/hms/test_hms.c +++ b/samples/sample_c/module_sample/hms/test_hms.c @@ -406,6 +406,8 @@ static bool DjiTest_MarchErrCodeInfoTableByJson(T_DjiHmsInfoTable hmsInfoTable) hmsInfoTable.hmsInfo[i].errorCode); } } + + cJSON_Delete(hmsJsonRoot); } static T_DjiReturnCode DjiTest_HmsInfoCallback(T_DjiHmsInfoTable hmsInfoTable) diff --git a/samples/sample_c/module_sample/liveview/test_liveview.c b/samples/sample_c/module_sample/liveview/test_liveview.c index 850df7a..090b69a 100644 --- a/samples/sample_c/module_sample/liveview/test_liveview.c +++ b/samples/sample_c/module_sample/liveview/test_liveview.c @@ -80,11 +80,10 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition) USER_LOG_INFO("--> Step 2: Start h264 stream of the fpv and selected payload\r\n"); DjiTest_WidgetLogAppend("--> Step 2: Start h264 stream of the fpv and selected payload\r\n"); - if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3E) { + if (aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M300 || + aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M350 || + aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M30) { - } else if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3T) { - - } else { localTime = localtime(¤tTime); sprintf(s_fpvCameraStreamFilePath, "fpv_stream_%04d%02d%02d_%02d-%02d-%02d.h264", localTime->tm_year + 1900, localTime->tm_mon + 1, localTime->tm_mday, @@ -127,11 +126,9 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition) USER_LOG_INFO("--> Step 3: Stop h264 stream of the fpv and selected payload\r\n"); DjiTest_WidgetLogAppend("--> Step 3: Stop h264 stream of the fpv and selected payload"); - if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3E) { - - } else if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3T) { - - } else { + if (aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M300 || + aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M350 || + aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M30) { returnCode = DjiLiveview_StopH264Stream(DJI_LIVEVIEW_CAMERA_POSITION_FPV, DJI_LIVEVIEW_CAMERA_SOURCE_DEFAULT); if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { USER_LOG_ERROR("Request to stop h264 of fpv failed, error code: 0x%08X", returnCode); @@ -149,7 +146,8 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition) USER_LOG_INFO("Fpv stream is saved to file: %s", s_fpvCameraStreamFilePath); USER_LOG_INFO("Payload%d stream is saved to file: %s\r\n", mountPosition, s_payloadCameraStreamFilePath); - if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3T) { + if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3T || + aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3TD) { USER_LOG_INFO("--> Start h264 stream of the fpv and selected payload\r\n"); localTime = localtime(¤tTime); diff --git a/samples/sample_c/module_sample/utils/util_link_list.c b/samples/sample_c/module_sample/utils/util_link_list.c new file mode 100644 index 0000000..ebd318b --- /dev/null +++ b/samples/sample_c/module_sample/utils/util_link_list.c @@ -0,0 +1,218 @@ +/** + ******************************************************************** + * @file util_link_list.c + * @brief + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +#define UTIL_LINK_LIST_C + +#ifdef __cplusplus +extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "util_link_list.h" + +/* Private constants ---------------------------------------------------------*/ + +/* Private types -------------------------------------------------------------*/ + +/* Private functions declaration ---------------------------------------------*/ + +/* Private values ------------------------------------------------------------*/ + +/* Exported functions definition ---------------------------------------------*/ +void DjiUserUtil_ListNodeDeleteDataOnly( T_UtilListNode *node ) +{ + if ( NULL == node) { + UTIL_REPORT_ERROR( "null pointer" ); + return; + } + + if ( NULL != node->data ) { + UTIL_OSAL_MEMRY_FREE( node->data ); + node->data = NULL; + } + return; +} + +void DjiUserUtil_ListNodeDeleteNodeSelf( T_UtilListNode *node ) +{ + if ( NULL == node) { + UTIL_REPORT_ERROR( "null pointer" ); + return; + } + + UTIL_OSAL_MEMRY_FREE( node ); + return; +} + +void DjiUserUtil_InitListNode( T_UtilListNode *node, void *data ) +{ + if ( NULL == node ) { + UTIL_REPORT_ERROR( "null pointer" ); + return; + } + + node->prev = NULL; + node->next = NULL; + node->data = data; + return; +} + +T_UtilListNode *DjiUserUtil_NewListNode( void *data ) +{ + T_UtilListNode *node = NULL; + + node = (T_UtilListNode *)UTIL_OSAL_MEMRY_ALLOC( sizeof(T_UtilListNode) ); + if ( NULL == node ) { + UTIL_REPORT_ERROR( "null pointer" ); + return NULL; + } + + DjiUserUtil_InitListNode( node, data ); + return node; +} + +void DjiUserUtil_LinkListDestory( T_UtilLinkList *linkList ) +{ + T_UtilListNode *node = NULL; + T_UtilListNode *next = NULL; + + if ( NULL == linkList ) { + UTIL_REPORT_ERROR( "null pointer" ); + return; + } + + for ( node = linkList->first; NULL != node ; node = next ) { + next = node->next; + DjiUserUtil_ListNodeDeleteDataOnly( node ); + DjiUserUtil_ListNodeDeleteNodeSelf( node ); + } +} +void DjiUserUtil_LinkListAddNodeFirst( T_UtilLinkList *linkList, T_UtilListNode *node ) +{ + if ( ( NULL == linkList ) || ( NULL == node ) ) { + UTIL_REPORT_ERROR( "null pointer" ); + return; + } + + if ( UTIL_LINKLIST_IS_EMPTY( *linkList ) ) { + node->prev = NULL; + node->next = NULL; + linkList->first = node; + linkList->last = node; + } else { + node->prev = NULL; + node->next = linkList->first; + linkList->first = node; + node->next->prev = node; + } + linkList->count ++; + return; +} + +void DjiUserUtil_LinkListAddNodeLast( T_UtilLinkList *linkList, T_UtilListNode *node ) +{ + if ( ( NULL == linkList ) || ( NULL == node ) ) { + UTIL_REPORT_ERROR( "null pointer" ); + return; + } + + if ( UTIL_LINKLIST_IS_EMPTY( *linkList ) ) { + node->prev = NULL; + node->next = NULL; + linkList->first = node; + linkList->last = node; + } else { + node->next = NULL; + node->prev = linkList->last; + linkList->last = node; + node->prev->next = node; + } + linkList->count ++; + return; +} + +void DjiUserUtil_InitLinkList( T_UtilLinkList *linkList ) +{ + if ( NULL == linkList ) { + UTIL_REPORT_ERROR( "null pointer" ); + return; + } + + linkList->first = NULL; + linkList->last = NULL; + linkList->count = 0; + return; +} + +T_UtilLinkList *DjiUserUtil_NewLinkList( void ) +{ + T_UtilLinkList *linkList = NULL; + + linkList = (T_UtilLinkList *)UTIL_OSAL_MEMRY_ALLOC( sizeof( T_UtilLinkList ) ); + if ( NULL == linkList ) { + UTIL_REPORT_ERROR( "null pointer" ); + return NULL; + } + + DjiUserUtil_InitLinkList( linkList ); + return linkList; +} + +void DjiUserUtil_LinkListRemoveNodeOnly( T_UtilLinkList *linkList, T_UtilListNode *node ) +{ + if ( ( NULL == linkList ) || ( NULL == node ) ) { + UTIL_REPORT_ERROR( "null pointer" ); + return; + } + + if ( node == linkList->first ) { + linkList->first = linkList->first->next; + } + + if ( node == linkList->last ) { + linkList->last = linkList->last->prev; + } + + if ( NULL != node->next ) { + node->next->prev = node->prev; + } + + if ( NULL != node->prev ) { + node->prev->next = node->next; + } + + if ( 0 != linkList->count ) { + linkList->count --; + } + + DjiUserUtil_ListNodeDeleteNodeSelf( node ); + return; +} +/* Private functions definition-----------------------------------------------*/ + +#ifdef __cplusplus +} +#endif + +/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/ diff --git a/samples/sample_c/module_sample/utils/util_link_list.h b/samples/sample_c/module_sample/utils/util_link_list.h new file mode 100644 index 0000000..240a87e --- /dev/null +++ b/samples/sample_c/module_sample/utils/util_link_list.h @@ -0,0 +1,94 @@ +/** + ******************************************************************** + * @file link_list.h + * @brief This is the header file for "link_list.c", defining the structure and + * (exported) function prototypes. + * + * @copyright (c) 2021 DJI. All rights reserved. + * + * All information contained herein is, and remains, the property of DJI. + * The intellectual and technical concepts contained herein are proprietary + * to DJI and may be covered by U.S. and foreign patents, patents in process, + * and protected by trade secret or copyright law. Dissemination of this + * information, including but not limited to data and other proprietary + * material(s) incorporated within the information, in any form, is strictly + * prohibited without the express written consent of DJI. + * + * If you receive this source code without DJI’s authorization, you may not + * further disseminate the information, and you must immediately remove the + * source code and notify DJI of its removal. DJI reserves the right to pursue + * legal actions against you for any loss(es) or damage(s) caused by your + * failure to do so. + * + ********************************************************************* + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef UTIL_LINK_LIST_H +#define UTIL_LINK_LIST_H + +/* Includes ------------------------------------------------------------------*/ +#include "dji_platform.h" + +#ifdef UTIL_LINK_LIST_C + #define UTIL_LINK_LIST_EXT +#else + #define UTIL_LINK_LIST_EXT extern +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +/* Exported constants --------------------------------------------------------*/ +#define UTIL_REPORT_ERROR( exp... ) + +#define UTIL_OSAL_MEMRY_ALLOC(size) ( { T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); osalHandler->Malloc( size ); } ) +#define UTIL_OSAL_MEMRY_FREE(ptr) ( { T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); osalHandler->Free( ptr ); } ) + +#define UTIL_OSAL_SEM_FREE_MAY_RETURN(sem) ( { T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); if( DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS != osalHandler->SemaphoreDestroy( sem ) ) { return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; } } ) +#define UTIL_OSAL_SEM_INIT_MAY_RETURN(sem) ( { T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); if( DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS != osalHandler->SemaphoreCreate( 0, sem ) ) { return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; } } ) +#define UTIL_OSAL_SEM_POST_MAY_RETURN(sem) ( { T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); if( DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS != osalHandler->SemaphorePost( sem ) ) { return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; } } ) +#define UTIL_OSAL_SEM_WAIT_MAY_RETURN(sem) ( { T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); if( DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS != osalHandler->SemaphoreWait( sem ) ) { return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; } } ) +#define UTIL_OSAL_SEM_WAIT_FOR(sem,ms) ( { T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); if( DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS != osalHandler->SemaphoreTimedWait( sem, ms ) ) { return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; } } ) + +#define UTIL_OSAL_MUTEX_FREE_MAY_RETURN(mutex) ( { T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); if( DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS != osalHandler->MutexDestroy( mutex ) ) { return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; } } ) +#define UTIL_OSAL_MUTEX_INIT_MAY_RETURN(mutex) ( { T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); if( DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS != osalHandler->MutexCreate( mutex ) ) { return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; } } ) +#define UTIL_OSAL_MUTEX_LOCK_MAY_RETURN(mutex) ( { T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); if( DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS != osalHandler->MutexLock( mutex ) ) { return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; } } ) +#define UTIL_OSAL_MUTEX_UNLOCK_MAY_RETURN(mutex) ( { T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler(); if( DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS != osalHandler->MutexUnlock( mutex ) ) { return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER; } } ) + +#define UTIL_LINKLIST_IS_EMPTY(l) ( ((l).first == NULL) ? true : false ) + +/* Exported types ------------------------------------------------------------*/ +typedef struct tagT_UtilListNode { + struct tagT_UtilListNode *next; + struct tagT_UtilListNode *prev; + void *data; +} T_UtilListNode; + +typedef struct tagT_UtilLinkList { + T_UtilListNode *first; + T_UtilListNode *last; + uint32_t count; +} T_UtilLinkList; + +/* Exported functions --------------------------------------------------------*/ +UTIL_LINK_LIST_EXT void DjiUserUtil_ListNodeDeleteDataOnly( T_UtilListNode *node ); +UTIL_LINK_LIST_EXT void DjiUserUtil_ListNodeDeleteNodeSelf( T_UtilListNode *node ); +UTIL_LINK_LIST_EXT void DjiUserUtil_InitListNode( T_UtilListNode *node, void *data ); +UTIL_LINK_LIST_EXT T_UtilListNode *DjiUserUtil_NewListNode( void *data ); + +UTIL_LINK_LIST_EXT void DjiUserUtil_LinkListDestory( T_UtilLinkList *linkList ); +UTIL_LINK_LIST_EXT void DjiUserUtil_LinkListAddNodeFirst( T_UtilLinkList *linkList, T_UtilListNode *node ); +UTIL_LINK_LIST_EXT void DjiUserUtil_LinkListAddNodeLast( T_UtilLinkList *linkList, T_UtilListNode *node ); +UTIL_LINK_LIST_EXT void DjiUserUtil_InitLinkList( T_UtilLinkList *linkList ); +UTIL_LINK_LIST_EXT T_UtilLinkList *DjiUserUtil_NewLinkList( void ); + +UTIL_LINK_LIST_EXT void DjiUserUtil_LinkListRemoveNodeOnly( T_UtilLinkList *linkList, T_UtilListNode *node ); + +#ifdef __cplusplus +} +#endif + +#endif // UTIL_LINK_LIST_H +/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/ diff --git a/samples/sample_c/module_sample/widget/test_widget_speaker.c b/samples/sample_c/module_sample/widget/test_widget_speaker.c index c28384f..5646515 100644 --- a/samples/sample_c/module_sample/widget/test_widget_speaker.c +++ b/samples/sample_c/module_sample/widget/test_widget_speaker.c @@ -322,7 +322,9 @@ static T_DjiReturnCode DjiTest_PlayTtsData(void) } if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3E || - aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3T) { + aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3T || + aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3D || + aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3TD) { return DjiTest_PlayAudioData(); } else { txtFile = fopen(WIDGET_SPEAKER_TTS_FILE_NAME, "r"); diff --git a/samples/sample_c/platform/linux/common/upgrade_platform_opt/upgrade_platform_opt_linux.c b/samples/sample_c/platform/linux/common/upgrade_platform_opt/upgrade_platform_opt_linux.c index 7928a43..8375e5d 100644 --- a/samples/sample_c/platform/linux/common/upgrade_platform_opt/upgrade_platform_opt_linux.c +++ b/samples/sample_c/platform/linux/common/upgrade_platform_opt/upgrade_platform_opt_linux.c @@ -132,7 +132,7 @@ T_DjiReturnCode DjiUpgradePlatformLinux_CreateUpgradeProgramFile(const T_DjiUpgr snprintf(filePath, DJI_FILE_PATH_SIZE_MAX, "%s%s", DJI_TEST_UPGRADE_FILE_DIR, fileInfo->fileName); s_upgradeProgramFile = fopen(filePath, "w+"); if (s_upgradeProgramFile == NULL) { - USER_LOG_ERROR("Upgrade program file can't create: \"%s\"", filePath); + USER_LOG_ERROR("Upgrade program file can't create"); return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR; } diff --git a/samples/sample_c/platform/linux/manifold2/application/main.c b/samples/sample_c/platform/linux/manifold2/application/main.c index 556436e..4e2306f 100644 --- a/samples/sample_c/platform/linux/manifold2/application/main.c +++ b/samples/sample_c/platform/linux/manifold2/application/main.c @@ -219,7 +219,7 @@ int main(int argc, char **argv) .cleanUpgradeRebootState = DjiUpgradePlatformLinux_CleanUpgradeRebootState, }; T_DjiTestUpgradeConfig testUpgradeConfig = { - .firmwareVersion = {1, 0, 0, 0}, + .firmwareVersion = firmwareVersion, .transferType = DJI_FIRMWARE_TRANSFER_TYPE_DCFTP, .needReplaceProgramBeforeReboot = true }; @@ -326,7 +326,7 @@ int main(int argc, char **argv) .cleanUpgradeRebootState = DjiUpgradePlatformLinux_CleanUpgradeRebootState, }; T_DjiTestUpgradeConfig testUpgradeConfig = { - .firmwareVersion = {1, 0, 0, 0}, + .firmwareVersion = firmwareVersion, .transferType = DJI_FIRMWARE_TRANSFER_TYPE_DCFTP, .needReplaceProgramBeforeReboot = true }; diff --git a/samples/sample_c/platform/linux/nvidia_jetson/application/main.c b/samples/sample_c/platform/linux/nvidia_jetson/application/main.c index 992b3e3..3e994e7 100644 --- a/samples/sample_c/platform/linux/nvidia_jetson/application/main.c +++ b/samples/sample_c/platform/linux/nvidia_jetson/application/main.c @@ -291,7 +291,7 @@ int main(int argc, char **argv) .cleanUpgradeRebootState = DjiUpgradePlatformLinux_CleanUpgradeRebootState, }; T_DjiTestUpgradeConfig testUpgradeConfig = { - .firmwareVersion = {1, 0, 0, 0}, + .firmwareVersion = firmwareVersion, .transferType = DJI_FIRMWARE_TRANSFER_TYPE_DCFTP, .needReplaceProgramBeforeReboot = true }; diff --git a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/FreeRTOSConfig.h b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/FreeRTOSConfig.h index 31b1898..5f3f010 100644 --- a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/FreeRTOSConfig.h +++ b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/FreeRTOSConfig.h @@ -64,7 +64,7 @@ #define configTICK_RATE_HZ ((TickType_t)1000) #define configMAX_PRIORITIES ( 7 ) #define configMINIMAL_STACK_SIZE ((uint16_t)128) -#define configTOTAL_HEAP_SIZE ((size_t)75000) +#define configTOTAL_HEAP_SIZE ((size_t)90000) #define configMAX_TASK_NAME_LEN ( 16 ) #define configUSE_16_BIT_TICKS 0 #define configUSE_MUTEXES 1 diff --git a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/application.c b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/application.c index 54bcdec..0dc533d 100644 --- a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/application.c +++ b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/application.c @@ -112,10 +112,10 @@ void DjiUser_StartTask(void const *argument) .UartGetStatus = HalUart_GetStatus, }; T_DjiFirmwareVersion firmwareVersion = { - .majorVersion = 1, - .minorVersion = 0, - .modifyVersion = 0, - .debugVersion = 0, + .majorVersion = USER_FIRMWARE_MAJOR_VERSION, + .minorVersion = USER_FIRMWARE_MINOR_VERSION, + .modifyVersion = USER_FIRMWARE_MODIFY_VERSION, + .debugVersion = USER_FIRMWARE_DEBUG_VERSION, }; UART_Init(DJI_CONSOLE_UART_NUM, DJI_CONSOLE_UART_BAUD); @@ -233,7 +233,6 @@ void DjiUser_StartTask(void const *argument) } #endif -#if !USE_USB_HOST_UART #ifdef CONFIG_MODULE_SAMPLE_CAMERA_ON if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK && aircraftInfoBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) { @@ -318,7 +317,12 @@ void DjiUser_StartTask(void const *argument) .cleanUpgradeRebootState = DjiUpgradePlatformStm32_CleanUpgradeRebootState, }; T_DjiTestUpgradeConfig testUpgradeConfig = { - .firmwareVersion = {1, 0, 0, 0}, + .firmwareVersion = { + USER_FIRMWARE_MAJOR_VERSION, + USER_FIRMWARE_MINOR_VERSION, + USER_FIRMWARE_MODIFY_VERSION, + USER_FIRMWARE_DEBUG_VERSION + }, .transferType = DJI_FIRMWARE_TRANSFER_TYPE_DCFTP, .needReplaceProgramBeforeReboot = false }; @@ -326,7 +330,6 @@ void DjiUser_StartTask(void const *argument) DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) { printf("psdk upgrade init error"); } -#endif #endif returnCode = DjiCore_ApplicationStart(); diff --git a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/dji_sdk_config.h b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/dji_sdk_config.h index db35fa9..e9d4860 100644 --- a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/dji_sdk_config.h +++ b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/dji_sdk_config.h @@ -44,11 +44,11 @@ extern "C" { #define CONFIG_MODULE_SAMPLE_FC_SUBSCRIPTION_ON -#define CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON +// #define CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON -#define CONFIG_MODULE_SAMPLE_CAMERA_ON +// #define CONFIG_MODULE_SAMPLE_CAMERA_ON -#define CONFIG_MODULE_SAMPLE_XPORT_ON +// #define CONFIG_MODULE_SAMPLE_XPORT_ON #define CONFIG_MODULE_SAMPLE_UPGRADE_ON diff --git a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/main.c b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/main.c index 5803cef..bf22f2e 100644 --- a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/main.c +++ b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/application/main.c @@ -27,6 +27,8 @@ #include "application.h" #include "FreeRTOS.h" #include "task.h" +#include "core_cm4.h" +#include "flash_if.h" /* Private constants ---------------------------------------------------------*/ #define USER_START_TASK_STACK_SIZE 2048 @@ -53,6 +55,10 @@ void Error_Handler(void); int main(void) { + __disable_irq(); + SCB->VTOR = APPLICATION_ADDRESS; + __enable_irq(); + /* STM32F4xx HAL library initialization: - Configure the Flash prefetch, instruction and Data caches - Configure the Systick to generate an interrupt each 1 msec diff --git a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/project/armgcc/STM32F407VGTX_FLASH.ld b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/project/armgcc/STM32F407VGTX_FLASH.ld index acd5cd3..0724af9 100644 --- a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/project/armgcc/STM32F407VGTX_FLASH.ld +++ b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/project/armgcc/STM32F407VGTX_FLASH.ld @@ -29,7 +29,7 @@ ENTRY(Reset_Handler) /* Highest address of the user mode stack */ -_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */ +_estack = ORIGIN(RAM) + LENGTH(RAM) - 4; /* end of "RAM" Ram type memory */ _Min_Heap_Size = 0x800 ; /* required amount of heap */ _Min_Stack_Size = 0x800 ; /* required amount of stack */ @@ -39,7 +39,7 @@ MEMORY { CCMRAM (xrw) : ORIGIN = 0x10000000, LENGTH = 64K RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K - FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 1024K + FLASH (rx) : ORIGIN = 0x8010000, LENGTH = 448K } /* Sections */ diff --git a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/project/mdk/mdk_app.uvprojx b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/project/mdk/mdk_app.uvprojx index 85a7b39..576f04f 100644 --- a/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/project/mdk/mdk_app.uvprojx +++ b/samples/sample_c/platform/rtos_freertos/stm32f4_discovery/project/mdk/mdk_app.uvprojx @@ -535,6 +535,11 @@ 1 +util_link_list.c +..\..\..\..\..\module_sample\utils\util_link_list.c + + +1 util_md5.c ..\..\..\..\..\module_sample\utils\util_md5.c