NEW: release DJI Payload-SDK version 3.12.0
This commit is contained in:
43
LICENSE.txt
43
LICENSE.txt
@ -310,36 +310,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_i2c.c
|
||||
│ │ │ │ ├── hal_i2c.h
|
||||
│ │ │ │ ├── hal_network.c
|
||||
│ │ │ │ ├── hal_network.h
|
||||
│ │ │ │ ├── hal_uart.c
|
||||
│ │ │ │ ├── hal_uart.h
|
||||
│ │ │ │ ├── hal_usb_bulk.c
|
||||
│ │ │ │ └── hal_usb_bulk.h
|
||||
│ │ │ ├── raspberry_pi
|
||||
│ │ │ │ ├── application
|
||||
│ │ │ │ │ ├── dji_sdk_app_info.h
|
||||
│ │ │ │ │ ├── dji_sdk_config.h
|
||||
│ │ │ │ │ └── main.c
|
||||
│ │ │ │ ├── CMakeLists.txt
|
||||
│ │ │ │ └── hal
|
||||
│ │ │ │ ├── hal_i2c.c
|
||||
│ │ │ │ ├── hal_i2c.h
|
||||
│ │ │ │ ├── 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
|
||||
|
||||
50
README.md
50
README.md
@ -1,8 +1,8 @@
|
||||
# DJI Payload SDK (PSDK)
|
||||
|
||||

|
||||

|
||||

|
||||

|
||||

|
||||

|
||||
|
||||
## What is the DJI Payload SDK?
|
||||
|
||||
@ -23,12 +23,48 @@ to get the latest version information.
|
||||
|
||||
## Latest Release
|
||||
|
||||
The latest release version of PSDK is 3.11.1. This version of Payload SDK mainly add some new features support and fixed some
|
||||
The latest release version of PSDK is 3.12.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.
|
||||
|
||||
* Fixed the issue where the Matrice 4D or Matrice 4TD E-Port Lite interface was not recognized on FlightHub 2.
|
||||
* Fixed the crash issue when using the DjiCore_Delnit interface.
|
||||
* Fixed the occasional crash issue when transmitting video streams through the USB bulk channel on Matrice 350 RTK.
|
||||
### 1. Matrice 400 Feature Support
|
||||
- **Added point cloud data subscription for LiDAR/millimeter-wave radar on aircraft.**
|
||||
- **Added custom widget management.**
|
||||
- **Added Expanded payload device support.**
|
||||
Supports up to 7 payload devices simultaneously, compatible with:
|
||||
- Skyport-V2
|
||||
- XPort
|
||||
|
||||
### 2. Manifold 3 Now Supports:
|
||||
- **Added AR image drawing function.**
|
||||
- **Added Enhanced warning functionality.**
|
||||
- **Added H30 camera image processing capabilities.**
|
||||
- Together with Matrice 400, Manifold 3 can:
|
||||
- Obtain decoded images from the H30 camera.
|
||||
- Encode using a hardware encoder.
|
||||
- Display AI recognition results in real time.
|
||||
- **Added PSDK application development**
|
||||
- Supports developing and packaging applications based on PSDK.
|
||||
- Supports installing and running applications on Manifold 3.
|
||||
|
||||
### 3. Matrice 4TD/4D Series Feature Optimization
|
||||
- **Added cloud API firmware upgrade**
|
||||
|
||||
### 4. E-PORT V2 Hardware Port Support
|
||||
- **Adapter compatibility:**
|
||||
- E-Port V2 coaxial cable
|
||||
- Skyport V3
|
||||
- **Power management:**
|
||||
- Supports voltage requests for 13.6V, 17V, and 24V.
|
||||
- **Link models:**
|
||||
- Added: ONLY_USB_BULK, ONLY_NETWORK.
|
||||
- Not supported: UART_AND_NETWORK, UART_AND_USB_BULK.
|
||||
- **Development support:**
|
||||
- Released DJI E-Port V2 development kit.
|
||||
- Documentation: Refer to the Quick Start > E-Port Quick Start section.
|
||||
|
||||
### 5. Upgrade and Compatibility
|
||||
#### SkyPort V2 and X-Port Software Upgrade
|
||||
The software versions of Skyport V2 and X-Port have been upgraded. Devices need to be mounted on the Matrice 300 or Matrice 350 to be upgraded to the latest software version before they can be used on the Matrice 400 model. Subsequent software upgrades can be performed on the Matrice 400.
|
||||
|
||||
## License
|
||||
|
||||
|
||||
60
psdk_lib/include/dji_cloud_api_by_websockt.h
Normal file
60
psdk_lib/include/dji_cloud_api_by_websockt.h
Normal file
@ -0,0 +1,60 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_cloud_api_by_websockt.h
|
||||
* @brief This is the header file for "dji_cloud_api_by_websockt.h", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef DJI_CLOUD_API_BY_WEEBSOCKET_H
|
||||
#define DJI_CLOUD_API_BY_WEEBSOCKET_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_typedef.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
|
||||
/**
|
||||
* @brief Send data into cloud api channel over pilot2 websocket.
|
||||
* @note This interface should be called only on manifold3 application. It is recommended
|
||||
* to send more bytes of data at a time to improve read and write efficiency. Need to determine whether the send is
|
||||
* successful according to the return code and the actual sent data length.
|
||||
* @param data: pointer to data to be sent.
|
||||
* @param len: length of data to be sented to pilot2, unit: byte.
|
||||
* @param realLen: pointer to real length of data that already sent.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiCloudApi_SendDataByWebSocket(uint8_t *data, uint32_t len, uint32_t *realLen);
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
|
||||
@ -526,6 +526,153 @@ typedef enum {
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_IMU_ATTI_NAVI_DATA_WITH_TIMESTAMP = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 48),
|
||||
|
||||
/*!
|
||||
* @brief Provides postion NO.1 gimbal pitch, roll, yaw @ up to 50Hz
|
||||
* @details
|
||||
* The reference frame for gimbal angles is a NED frame attached to the gimbal.
|
||||
* This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is :
|
||||
* |Data Structure Element| Meaning|
|
||||
* |----------------------|--------|
|
||||
* |Vector3f.x |pitch |
|
||||
* |Vector3f.y |roll |
|
||||
* |Vector3f.z |yaw |
|
||||
*
|
||||
* @perf
|
||||
* 0.1 deg accuracy in all axes
|
||||
*
|
||||
* @sensors Gimbal Encoder, IMU, Magnetometer
|
||||
* @units deg
|
||||
* @datastruct \ref T_DjiFcSubscriptionGimbalAngles
|
||||
* @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO1 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 48),
|
||||
|
||||
/*!
|
||||
* @brief Provides postion NO.2 gimbal pitch, roll, yaw @ up to 50Hz
|
||||
* @details
|
||||
* The reference frame for gimbal angles is a NED frame attached to the gimbal.
|
||||
* This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is :
|
||||
* |Data Structure Element| Meaning|
|
||||
* |----------------------|--------|
|
||||
* |Vector3f.x |pitch |
|
||||
* |Vector3f.y |roll |
|
||||
* |Vector3f.z |yaw |
|
||||
*
|
||||
* @perf
|
||||
* 0.1 deg accuracy in all axes
|
||||
*
|
||||
* @sensors Gimbal Encoder, IMU, Magnetometer
|
||||
* @units deg
|
||||
* @datastruct \ref T_DjiFcSubscriptionGimbalAngles
|
||||
* @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO2 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 49),
|
||||
|
||||
/*!
|
||||
* @brief Provides postion NO.3 gimbal pitch, roll, yaw @ up to 50Hz
|
||||
* @details
|
||||
* The reference frame for gimbal angles is a NED frame attached to the gimbal.
|
||||
* This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is :
|
||||
* |Data Structure Element| Meaning|
|
||||
* |----------------------|--------|
|
||||
* |Vector3f.x |pitch |
|
||||
* |Vector3f.y |roll |
|
||||
* |Vector3f.z |yaw |
|
||||
*
|
||||
* @perf
|
||||
* 0.1 deg accuracy in all axes
|
||||
*
|
||||
* @sensors Gimbal Encoder, IMU, Magnetometer
|
||||
* @units deg
|
||||
* @datastruct \ref T_DjiFcSubscriptionGimbalAngles
|
||||
* @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO3 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 50),
|
||||
|
||||
/*!
|
||||
* @brief Provides postion NO.4 gimbal pitch, roll, yaw @ up to 50Hz
|
||||
* @details
|
||||
* The reference frame for gimbal angles is a NED frame attached to the gimbal.
|
||||
* This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is :
|
||||
* |Data Structure Element| Meaning|
|
||||
* |----------------------|--------|
|
||||
* |Vector3f.x |pitch |
|
||||
* |Vector3f.y |roll |
|
||||
* |Vector3f.z |yaw |
|
||||
*
|
||||
* @perf
|
||||
* 0.1 deg accuracy in all axes
|
||||
*
|
||||
* @sensors Gimbal Encoder, IMU, Magnetometer
|
||||
* @units deg
|
||||
* @datastruct \ref T_DjiFcSubscriptionGimbalAngles
|
||||
* @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO4 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 51),
|
||||
|
||||
/*!
|
||||
* @brief Provides postion NO.5 gimbal pitch, roll, yaw @ up to 50Hz
|
||||
* @details
|
||||
* The reference frame for gimbal angles is a NED frame attached to the gimbal.
|
||||
* This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is :
|
||||
* |Data Structure Element| Meaning|
|
||||
* |----------------------|--------|
|
||||
* |Vector3f.x |pitch |
|
||||
* |Vector3f.y |roll |
|
||||
* |Vector3f.z |yaw |
|
||||
*
|
||||
* @perf
|
||||
* 0.1 deg accuracy in all axes
|
||||
*
|
||||
* @sensors Gimbal Encoder, IMU, Magnetometer
|
||||
* @units deg
|
||||
* @datastruct \ref T_DjiFcSubscriptionGimbalAngles
|
||||
* @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO5 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 52),
|
||||
|
||||
/*!
|
||||
* @brief Provides postion NO.6 gimbal pitch, roll, yaw @ up to 50Hz
|
||||
* @details
|
||||
* The reference frame for gimbal angles is a NED frame attached to the gimbal.
|
||||
* This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is :
|
||||
* |Data Structure Element| Meaning|
|
||||
* |----------------------|--------|
|
||||
* |Vector3f.x |pitch |
|
||||
* |Vector3f.y |roll |
|
||||
* |Vector3f.z |yaw |
|
||||
*
|
||||
* @perf
|
||||
* 0.1 deg accuracy in all axes
|
||||
*
|
||||
* @sensors Gimbal Encoder, IMU, Magnetometer
|
||||
* @units deg
|
||||
* @datastruct \ref T_DjiFcSubscriptionGimbalAngles
|
||||
* @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO6 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 53),
|
||||
|
||||
/*!
|
||||
* @brief Provides postion NO.7 gimbal pitch, roll, yaw @ up to 50Hz
|
||||
* @details
|
||||
* The reference frame for gimbal angles is a NED frame attached to the gimbal.
|
||||
* This topic uses a data structure, Vector3f, that is too generic for the topic. The order of angles is :
|
||||
* |Data Structure Element| Meaning|
|
||||
* |----------------------|--------|
|
||||
* |Vector3f.x |pitch |
|
||||
* |Vector3f.y |roll |
|
||||
* |Vector3f.z |yaw |
|
||||
*
|
||||
* @perf
|
||||
* 0.1 deg accuracy in all axes
|
||||
*
|
||||
* @sensors Gimbal Encoder, IMU, Magnetometer
|
||||
* @units deg
|
||||
* @datastruct \ref T_DjiFcSubscriptionGimbalAngles
|
||||
* @also \ref TOPIC_GIMBAL_STATUS, \ref TOPIC_GIMBAL_CONTROL_MODE
|
||||
*/
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO7 = DJI_DATA_SUBSCRIPTION_TOPIC(DJI_DATA_SUBSCRIPTION_MODULE_FC, 54),
|
||||
|
||||
/*! Total number of topics that can be subscribed. */
|
||||
DJI_FC_SUBSCRIPTION_TOPIC_TOTAL_NUMBER,
|
||||
} E_DjiFcSubscriptionTopic;
|
||||
|
||||
@ -237,6 +237,17 @@ typedef enum {
|
||||
DJI_FLIGHT_CONTROLLER_DISABLE_RC_LOST_ACTION = 1,
|
||||
} E_DjiFlightControllerRCLostActionEnableStatus;
|
||||
|
||||
typedef enum {
|
||||
DJI_FLIGHT_CONTROLLER_NO_MOTOR_IN_SLOW_ROTATE_MODE = 0,
|
||||
DJI_FLIGHT_CONTROLLER_SOME_MOTOR_IN_SLOW_ROTATE_MODE = 1,
|
||||
DJI_FLIGHT_CONTROLLER_ALL_MOTOR_IN_SLOW_ROTATE_MODE = 2,
|
||||
} E_DjiFlightControllerElectronicSpeedControllerStatus;
|
||||
|
||||
typedef enum {
|
||||
DJI_FLIGHT_CONTROLLER_FTS_NOT_TRIGGERD = 0,
|
||||
DJI_FLIGHT_CONTROLLER_FTS_TRIGGERD = 1,
|
||||
} E_DjiFlightControllerFtsStatus;
|
||||
|
||||
/**
|
||||
* @brief Joystick mode.
|
||||
* @note You need to set joystick mode first before start to send joystick command to aircraft.
|
||||
@ -274,6 +285,16 @@ typedef struct {
|
||||
|
||||
#pragma pack()
|
||||
|
||||
typedef struct {
|
||||
E_DjiMountPosition fts_select;
|
||||
E_DjiFlightControllerFtsStatus fts_status;
|
||||
uint8_t fts_pwm_cnt; /* correct number of PWM signals received */
|
||||
} T_DjiFtsPwmTriggerStatus;
|
||||
|
||||
typedef struct {
|
||||
T_DjiFtsPwmTriggerStatus ESC[2]; /* trigger status of the two ESCs */
|
||||
} T_DjiFtsPwmEscTriggerStatus;
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Initialise flight controller module
|
||||
@ -649,6 +670,38 @@ DjiFlightController_GetEnableRCLostActionStatus(E_DjiFlightControllerRCLostActio
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_RegTriggerFtsEventCallback(TriggerFtsEventCallback callback);
|
||||
|
||||
/**
|
||||
* @brief Start to rotate motors slowly.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_StartSlowRotateMotor(void);
|
||||
|
||||
/**
|
||||
* @brief Stop to rotate motors slowly.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_StopSlowRotateMotor(void);
|
||||
|
||||
/**
|
||||
* @brief Get the status of the ESC.
|
||||
* @param status: The status of the motor on aircraft.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_GetElectronicSpeedControllerStatus(E_DjiFlightControllerElectronicSpeedControllerStatus *status);
|
||||
|
||||
/**
|
||||
* @brief Select Fts pwm trigger.
|
||||
* @param position: Pwm trigger source position.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_SelectFtsPwmTrigger(E_DjiMountPosition position);
|
||||
|
||||
/**
|
||||
* @brief Get Fts pwm trigger status.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiFlightController_GetFtsPwmTriggerStatus(T_DjiFtsPwmEscTriggerStatus* trigger_status);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -44,6 +44,18 @@ typedef enum {
|
||||
DJI_HMS_ERROR_LEVEL_FATAL,
|
||||
} E_DjiHmsErrorLevel;
|
||||
|
||||
typedef enum {
|
||||
DJI_HMS_ALARM_ENHANCED_TYPE_SHAKE_MOTOR = 1, /*!< Alarm triggered by shaking the motor on the pilot; alerts the user with vibrations indicating a warning or fault. */
|
||||
DJI_HMS_ALARM_ENHANCED_PLAY_SOUND = 2, /*!< Alarm triggered by playing sound */
|
||||
DJI_HMS_ALARM_ENHANCED_PLAY_SOUND_AND_SHAKE_MOTOR =3, /*!< Alarm that alerts the user on the PILOT app with both sound and vibrations */
|
||||
} E_DjiHmsAlarmEnhancedType;
|
||||
|
||||
typedef enum {
|
||||
DJI_HMS_ALARM_ENHANCED_ACTION_STOP = 0, /*!< Action to stop a specific enhanced alarm, shake motor or play sound */
|
||||
DJI_HMS_ALARM_ENHANCED_ACTION_START = 1, /*!< Action to stop a specific enhanced alarm */
|
||||
DJI_HMS_ALARM_ENHANCED_ACTION_EXIT_ALL =2,/*!< Action to exit all enhanced alarms, both shake motor and play sound; */
|
||||
} E_DjiHmsAlarmEnhancedAction;
|
||||
|
||||
typedef struct {
|
||||
char *fileName; /*!< The file name of the hms text config file */
|
||||
uint32_t fileSize; /*!< The file size of the hms text config file, uint : byte */
|
||||
@ -55,6 +67,12 @@ typedef struct {
|
||||
T_DjiHmsFileBinaryArray *fileBinaryArrayList; /*!< Pointer to binary array list */
|
||||
} T_DjiHmsBinaryArrayConfig;
|
||||
|
||||
typedef struct {
|
||||
E_DjiHmsAlarmEnhancedType type; /*!< The type is used to specify which enhanced alarm to ACTION_STOP or ACTION_START. It is ignored when EXIT_ALL alarms.*/
|
||||
int8_t times; /* !< Specifies the number of consecutive times the alarm is to be activated.*/
|
||||
int16_t interval; /* !< Indicates the interval (in milliseconds) between consecutive activations of the alarm.*/
|
||||
} T_DjiHmsAlarmEnhancedSetting;
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Initialise hms customization module, and user should call this function
|
||||
@ -124,6 +142,15 @@ T_DjiReturnCode DjiHmsCustomization_RegDefaultHmsTextConfigByBinaryArray(const T
|
||||
T_DjiReturnCode DjiHmsCustomization_RegHmsTextConfigByBinaryArray(E_DjiMobileAppLanguage appLanguage,
|
||||
const T_DjiHmsBinaryArrayConfig *binaryArrayConfig);
|
||||
|
||||
/**
|
||||
* @brief Contrl the app alram.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @param action: The action to start or stop alarm.
|
||||
* @param setting: The alarm information.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiHmsCustomization_AlarmEnhancedCtrl(E_DjiHmsAlarmEnhancedAction action, T_DjiHmsAlarmEnhancedSetting setting);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -39,16 +39,23 @@ extern "C" {
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
typedef enum {
|
||||
DJI_INTEREST_POINT_MISSION_ACTION_STATE_NOT_STARTED = 0,
|
||||
DJI_INTEREST_POINT_MISSION_ACTION_STATE_PAUSE = 1,
|
||||
DJI_INTEREST_POINT_MISSION_ACTION_STATE_RUNNING = 2,
|
||||
} E_DjiInterestPointActionState;
|
||||
|
||||
typedef struct {
|
||||
dji_f32_t curSpeed;
|
||||
dji_f32_t radius;
|
||||
uint8_t state;
|
||||
uint8_t state; /*!< Refer to E_DjiInterestPointActionState.*/
|
||||
} T_DjiInterestPointMissionState;
|
||||
|
||||
typedef struct {
|
||||
dji_f64_t latitude;
|
||||
dji_f64_t longitude;
|
||||
dji_f32_t speed;
|
||||
int8_t payloadCameraIndex; /*!< Used by which aircraft that can mount payload cameras. Range starts from 1.*/
|
||||
} T_DjiInterestPointSettings;
|
||||
|
||||
typedef T_DjiReturnCode (*InterestPointMissionStateCallback)(T_DjiInterestPointMissionState missionState);
|
||||
|
||||
@ -47,6 +47,15 @@ typedef enum {
|
||||
DJI_LIVEVIEW_CAMERA_POSITION_FPV = 7
|
||||
} E_DjiLiveViewCameraPosition;
|
||||
|
||||
/**
|
||||
* @brief Image format.
|
||||
*/
|
||||
typedef enum {
|
||||
PIXFMT_NV12 = 3,
|
||||
PIXFMT_RGB_PLANAR = 4,
|
||||
PIXFMT_RGB_PACKED = 5
|
||||
} E_DjiLiveViewPixFormate;
|
||||
|
||||
/**
|
||||
* @brief Liveview camera stream source.
|
||||
*/
|
||||
@ -71,6 +80,8 @@ typedef enum {
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M3D_VIS = 1,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M3TD_VIS = 1,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M3TD_IR = 2,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_H30_ZOOM = 1,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_H30_4K = 7,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M4E_VIS = 1,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M4T_VIS = 1,
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M4T_IR = 2,
|
||||
@ -79,11 +90,91 @@ typedef enum {
|
||||
DJI_LIVEVIEW_CAMERA_SOURCE_M4TD_IR = 2,
|
||||
} E_DjiLiveViewCameraSource;
|
||||
|
||||
/**
|
||||
* @brief DJI standard types of target recognition.
|
||||
*/
|
||||
typedef enum {
|
||||
DJI_LIVEVIEW_OBJ_TYPE_INVALID = 0,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_UNKNOWN = 1,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_PERSON = 2,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_CAR = 3,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_BOAT = 4,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_HUMAN_FACE = 5,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_BIRD = 10,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_BEACON = 20,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_GPS = 30,
|
||||
DJI_LIVEVIEW_OBJ_TYPE_MOVING_TARGET = 34,
|
||||
} E_DjiLiveViewTargetObjectType;
|
||||
|
||||
/**
|
||||
* @brief Target Recognition Status.
|
||||
*/
|
||||
typedef enum {
|
||||
DJI_LIVEVIEW_OBJ_STATE_INVALID = 0, /*!< invalid state */
|
||||
DJI_LIVEVIEW_OBJ_STATE_TRACKED = 1, /*!< steady state following */
|
||||
DJI_LIVEVIEW_OBJ_STATE_VISION_BEACON_FUSIONED = 2, /*!< Vision beacon fusion state */
|
||||
DJI_LIVEVIEW_OBJ_STATE_AUXILIARY_TRACKED = 3, /*!< Loss of trigger source, auxiliary observation following state */
|
||||
DJI_LIVEVIEW_OBJ_STATE_NOT_CONFIDENT = 4, /*!< unstable following state */
|
||||
DJI_LIVEVIEW_OBJ_STATE_LOST_WITH_PREDICT = 5, /*!< Target lost, forecast status maintained */
|
||||
DJI_LIVEVIEW_OBJ_STATE_LOST = 6, /*!< Target Loss Status */
|
||||
DJI_LIVEVIEW_OBJ_STATE_REDETECTED = 7, /*!< Target Loss Retrieval Status */
|
||||
} E_DjiLiveViewTargetObjectState;
|
||||
|
||||
/**
|
||||
* @brief Picture frame information for target recognition results
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint16_t cx; /*!< X-coordinate of the center of the frame, unit: 1/10000 * screen width */
|
||||
uint16_t cy; /*!< Y-coordinate of the center of the frame, unit: 1/10000 * screen height */
|
||||
uint16_t w; /*!< Frame width, unit: 1/10000 * screen width */
|
||||
uint16_t h; /*!< Frame height, unit: 1/10000 * screen height */
|
||||
uint32_t distance; /*!< Distance in mm */
|
||||
} __attribute__((packed)) T_DjiLiveViewTarget2dBox;
|
||||
|
||||
/**
|
||||
* @brief BoundingBox information for target recognition.
|
||||
*/
|
||||
typedef struct {
|
||||
uint16_t id;
|
||||
uint8_t type; /*!< type can be an enumerated value of E_DjiLiveViewTargetObjectType or a user-defined value. */
|
||||
uint8_t state; /*!< state should be of type E_DjiLiveViewTargetObjectState enumeration */
|
||||
T_DjiLiveViewTarget2dBox box;
|
||||
} __attribute__((packed)) T_DjiLiveViewBoundingBox;
|
||||
|
||||
/**
|
||||
* @brief List of boundingBox information.
|
||||
*/
|
||||
typedef struct {
|
||||
uint8_t boxCount;
|
||||
T_DjiLiveViewBoundingBox boxData[1];
|
||||
} __attribute__((packed)) T_DjiLiveViewStandardMetaData;
|
||||
|
||||
/**
|
||||
* @brief Image information.
|
||||
*/
|
||||
typedef struct {
|
||||
E_DjiLiveViewPixFormate pixFmt;
|
||||
uint16_t width;
|
||||
uint16_t height;
|
||||
uint32_t frameId;
|
||||
} T_DjiLiveviewImageInfo;
|
||||
|
||||
/**
|
||||
* @brief Liveview camera h264 stream callback.
|
||||
*/
|
||||
typedef void (*DjiLiveview_H264Callback)(E_DjiLiveViewCameraPosition position, const uint8_t *buf, uint32_t len);
|
||||
|
||||
/**
|
||||
* @brief Liveview camera image data callback.
|
||||
*/
|
||||
typedef void (*DjiLiveview_ImageCallback)(E_DjiLiveViewCameraPosition position, const uint8_t *buf,
|
||||
uint32_t len , T_DjiLiveviewImageInfo ImageInfo);
|
||||
|
||||
/**
|
||||
* @brief Callback for handling encoded output data
|
||||
*/
|
||||
typedef void (*DjiLiveview_EncoderCallback)(const uint8_t *buf, uint32_t len);
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Initialize the liveview module.
|
||||
@ -125,6 +216,81 @@ T_DjiReturnCode DjiLiveview_StopH264Stream(E_DjiLiveViewCameraPosition position,
|
||||
T_DjiReturnCode DjiLiveview_RequestIntraframeFrameData(E_DjiLiveViewCameraPosition position,
|
||||
E_DjiLiveViewCameraSource source);
|
||||
|
||||
/**
|
||||
* @brief Request to get the decoded image data from the specified position.
|
||||
* @param position: Camera position for the H264 stream.
|
||||
* @param source: sub-camera source for the H264 stream.
|
||||
* @param pixFmt: Requested Image Format.
|
||||
* @param callback: Callback for handling image data.
|
||||
* @return Execution result.
|
||||
* @note This interface support on DJI manifold3.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_StartImageStream(E_DjiLiveViewCameraPosition position, E_DjiLiveViewCameraSource source,
|
||||
E_DjiLiveViewPixFormate pixFmt, DjiLiveview_ImageCallback callback);
|
||||
|
||||
/**
|
||||
* @brief Stop the decoded image data from the specified position.
|
||||
* @param position: Camera position for the H264 stream.
|
||||
* @param source: sub-camera source for the H264 stream.
|
||||
* @return Execution result.
|
||||
* @note This interface support on DJI manifold3.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_StopImageStream(E_DjiLiveViewCameraPosition position, E_DjiLiveViewCameraSource source);
|
||||
|
||||
/**
|
||||
* @brief Registering encoder callback handlers.
|
||||
* @return Execution result.
|
||||
* @note This interface support on DJI manifold3.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_RegEncoderCallback(DjiLiveview_EncoderCallback callback);
|
||||
|
||||
/**
|
||||
* @brief Unregistering encoder callback handlers.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_UnregEncoderCallback();
|
||||
|
||||
/**
|
||||
* @brief Encoding image into h264 streams.
|
||||
* @param buf: raw data of image.
|
||||
* @param len: length of image data.
|
||||
* @param imageInfo: information of image.
|
||||
* @param metaData: Resulting information obtained from images for target recognition.
|
||||
* @return Execution result.
|
||||
* @note If there is no need for information related to target identification, fill in NULL for metaData.
|
||||
* @note This interface needs to be used after DjiLiveview_RegEncoderCallback.
|
||||
* @note This interface support on DJI manifold3.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_EncodeAFrameToH264(const uint8_t *buf, uint32_t len, T_DjiLiveviewImageInfo imageInfo,
|
||||
T_DjiLiveViewStandardMetaData *metaData);
|
||||
|
||||
/**
|
||||
* @brief Register user-defined target Lables
|
||||
* @param lableCount: Number of lable.
|
||||
* @param labels: lable String Array
|
||||
* @note The key-value pairs of lable and index will be recorded on the Pilot after registration
|
||||
* and will be used to parse the metaData and display the lable when rendering the boundingbox.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_RegUserAiTargetLableList(uint8_t lableCount,const char *labels[]);
|
||||
|
||||
/**
|
||||
* @brief Unregister user-defined target Lables
|
||||
* @return Execution result.
|
||||
* @note This interface support on DJI manifold3.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_UnregUserAiTargetLableList();
|
||||
|
||||
/**
|
||||
* @brief Transmits the result information of the target recognition to the pilot for display.
|
||||
* @param metaData: Resulting information obtained from images for target recognition.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_SendAiMetaToPilot(T_DjiLiveViewStandardMetaData *metaData);
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -102,14 +102,24 @@ T_DjiReturnCode DjiLogger_RemoveConsole(T_DjiLoggerConsole *console);
|
||||
void DjiLogger_UserLogOutput(E_DjiLoggerConsoleLogLevel level, const char *fmt, ...);
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
#define __FILENAME__ (strrchr("/" __FILE__, '/') + 1)
|
||||
|
||||
#define USER_LOG_PREFIX_FMT "%25s:%-4d "
|
||||
|
||||
#ifndef SYSTEM_ARCH_RTOS
|
||||
#define USER_LOG_PREFIX_ARG __FILENAME__, __LINE__
|
||||
#else
|
||||
#define USER_LOG_PREFIX_ARG __FUNCTION__, __LINE__
|
||||
#endif
|
||||
|
||||
#define USER_LOG_DEBUG(fmt, ...) \
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_DEBUG, "[%s:%d) " fmt, __FUNCTION__, __LINE__ , ##__VA_ARGS__)
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_DEBUG, USER_LOG_PREFIX_FMT fmt, USER_LOG_PREFIX_ARG, ##__VA_ARGS__)
|
||||
#define USER_LOG_INFO(fmt, ...) \
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO, "[%s:%d) " fmt, __FUNCTION__, __LINE__ , ##__VA_ARGS__)
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO, USER_LOG_PREFIX_FMT fmt, USER_LOG_PREFIX_ARG, ##__VA_ARGS__)
|
||||
#define USER_LOG_WARN(fmt, ...) \
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_WARN, "[%s:%d) " fmt, __FUNCTION__, __LINE__ , ##__VA_ARGS__)
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_WARN, USER_LOG_PREFIX_FMT fmt, USER_LOG_PREFIX_ARG, ##__VA_ARGS__)
|
||||
#define USER_LOG_ERROR(fmt, ...) \
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_ERROR, "[%s:%d) " fmt, __FUNCTION__, __LINE__ , ##__VA_ARGS__)
|
||||
DjiLogger_UserLogOutput(DJI_LOGGER_CONSOLE_LOG_LEVEL_ERROR, USER_LOG_PREFIX_FMT fmt, USER_LOG_PREFIX_ARG, ##__VA_ARGS__)
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
||||
389
psdk_lib/include/dji_open_ar.h
Normal file
389
psdk_lib/include/dji_open_ar.h
Normal file
@ -0,0 +1,389 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_open_ar.h
|
||||
* @brief This is the header file for "dji_open_ar.c", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef DJI_OPEN_AR_H
|
||||
#define DJI_OPEN_AR_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_typedef.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
typedef struct
|
||||
{
|
||||
float longitude;
|
||||
float latitude;
|
||||
float altitude;
|
||||
} T_DjiOpenArCoordinate;
|
||||
|
||||
/**
|
||||
* @brief Text information definition
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t is_show:1; /*!< Whether to display, 0: not display, 1: display */
|
||||
uint8_t text[30]; /*!< Text information, with '\0' as the terminator */
|
||||
} T_DjiOpenArTextAttribute;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint8_t selected:1; /*!< Whether selected, 0: not selected, 1: selected */
|
||||
uint8_t visible :1; /*!< Whether to display, 0: not display, 1: display */
|
||||
uint32_t color; /*!< Contains alpha channel */
|
||||
} T_DjiOpenArIconAttribute;
|
||||
|
||||
/**
|
||||
* @brief Click action for a point
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t action; /*!< 0: click; 1: drag along the line; 2: drag from a distance */
|
||||
T_DjiOpenArCoordinate normal_vector; /*!< Dragging direction: normal vector */
|
||||
} T_DjiOpenArTouchAttribute;
|
||||
|
||||
/**
|
||||
* @brief Represents the unique identifier for AR elements
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint32_t uuid; /*!< uuid used for updating and deleting */
|
||||
uint32_t style_id; /*!< used to index resources config, corresponding resource is configured in widget.json */
|
||||
} T_DjiOpenArIds;
|
||||
|
||||
/**
|
||||
* @brief AR face drawing attributes
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t dist_alpha_enable :1; /*!< Enable distance-based alpha blending (1) or not (0) */
|
||||
uint8_t face_bottom_enable:1; /*!< Enable drawing bottom face (1) or not (0) */
|
||||
uint8_t face_side_enable :1; /*!< Enable drawing side face (1) or not (0) */
|
||||
uint8_t face_top_enable :1; /*!< Enable drawing top face (1) or not (0) */
|
||||
} T_DjiOpenArPolygonFaceAttribute;
|
||||
|
||||
/**
|
||||
* @brief AR border drawing attributes
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint8_t top_show :1;
|
||||
uint8_t top_dist_alpha_enable :1;
|
||||
uint8_t side_show :1;
|
||||
uint8_t side_dist_alpha_enable :1;
|
||||
uint8_t bottom_show :1;
|
||||
uint8_t bottom_dist_alpha_enable:1;
|
||||
} T_DjiOpenArPolygonStrokeAttribute;
|
||||
|
||||
/**
|
||||
* @brief AR pint drawing attibutes
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint32_t uuid; /*!< uuid for point , used to updating and delting */
|
||||
uint32_t style_id; /*!< dentifier for the style associated with the point, define with widget.json */
|
||||
uint32_t resource_id; /*!< Identifier for the resource associated with the point */
|
||||
uint8_t is_always_in_edge; /*!< Whether the point is always on the edge */
|
||||
T_DjiOpenArCoordinate coordinate; /*!< Physical position in the world coordinate system */
|
||||
T_DjiOpenArTextAttribute text_attr; /*!< Attributes related to the text associated with the point */
|
||||
T_DjiOpenArIconAttribute icon_attr; /*!< Attributes related to the icon associated with the point */
|
||||
T_DjiOpenArTouchAttribute touch_attr; /*!< Attributes related to touch interactions with the point */
|
||||
} T_DjiOpenArPoint;
|
||||
|
||||
/**
|
||||
* @brief Array of points
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint32_t len; /*!< Length of the array (number of points) */
|
||||
T_DjiOpenArPoint points[0]; /*!< 0 length implies dynamic allocation */
|
||||
} T_DjiOpenArPointArray;
|
||||
|
||||
/**
|
||||
* @biref AR Drawing Line
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
T_DjiOpenArIds ids; /*!< uuids for the AR line */
|
||||
T_DjiOpenArPointArray point_array; /*!< Array of points defining the line */
|
||||
} T_DjiOpenArLine;
|
||||
|
||||
/**
|
||||
* @brief AR Drawing Polygon
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
T_DjiOpenArIds ids; /*!< Unique identifiers for the AR polygon */
|
||||
T_DjiOpenArCoordinate normal_vector; /*!< Normal vector of the polygon surface */
|
||||
T_DjiOpenArPolygonFaceAttribute face; /*!< Face attributes of the polygon */
|
||||
T_DjiOpenArPolygonStrokeAttribute stroke; /*!< Stroke attributes of the polygon */
|
||||
T_DjiOpenArPointArray point_array; /*!< Array of points defining the polygon */
|
||||
} T_DjiOpenArPolygon;
|
||||
|
||||
/**
|
||||
* @brief AR Drawing Circle
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
T_DjiOpenArIds ids; /*!< Unique identifiers for the AR circle */
|
||||
float radius; /*!< Radius of the circle */
|
||||
T_DjiOpenArCoordinate center; /*!< Center coordinates of the circle */
|
||||
T_DjiOpenArCoordinate normal_vector; /*!< Normal vector of the circle's surface */
|
||||
T_DjiOpenArPolygonFaceAttribute face; /*!< Face attributes of the circle */
|
||||
T_DjiOpenArPolygonStrokeAttribute stroke; /*!< Stroke attributes of the circle */
|
||||
} T_DjiOpenArCircle;
|
||||
|
||||
/**
|
||||
* @brief AR Drawing 3D Cone Pivot Axis
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
T_DjiOpenArIds ids; /*!< Unique identifiers for the 3D cone */
|
||||
uint8_t show_enable; /*!< Flag indicating if the cone should be displayed (1) or not (0) */
|
||||
T_DjiOpenArCoordinate pivot; /*!< Center point of the cone */
|
||||
T_DjiOpenArCoordinate normal_vector; /*!< Normal vector for the cone's surface */
|
||||
} T_DjiOpenArPivotAxis;
|
||||
|
||||
/**
|
||||
* @brief eletion Entry for Specified Point, Face, Line, etc.
|
||||
*/
|
||||
typedef struct
|
||||
{
|
||||
uint32_t resource_id; /*!< Resource ID for the element to be deleted */
|
||||
uint32_t uuid_len; /*!< Length of the UUID array */
|
||||
uint32_t uuid_array[0]; /*!< Array of UUIDs to identify the elements to be deleted */
|
||||
} T_DjiOpenArDeletePointEntry;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint32_t uuid;
|
||||
} T_DjiOpenArDeleteCommonEntry;
|
||||
|
||||
/**
|
||||
* @brief Typedef for deletion of line entries
|
||||
*/
|
||||
typedef T_DjiOpenArDeleteCommonEntry T_DjiOpenArDeleteLineEntry;
|
||||
|
||||
/**
|
||||
* @brief Typedef for deletion of polygon entries
|
||||
*/
|
||||
typedef T_DjiOpenArDeleteCommonEntry T_DjiOpenArDeletePolygonEntry;
|
||||
|
||||
/**
|
||||
* @brief Typedef for deletion of circle entries
|
||||
*/
|
||||
typedef T_DjiOpenArDeleteCommonEntry T_DjiOpenArDeleteCircleEntry;
|
||||
|
||||
/**
|
||||
* @brief Typedef for deletion of pivot axis entries
|
||||
*/
|
||||
typedef T_DjiOpenArDeleteCommonEntry T_DjiOpenArDeletePovixAxisEntry;
|
||||
|
||||
/**
|
||||
* @brief Set the ar point.
|
||||
* @param metaData: the information for Ar point.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArSetPoint(const T_DjiOpenArPointArray* entry);
|
||||
|
||||
/**
|
||||
* @brief Update the ar point.
|
||||
* @param metaData: the information for Ar point.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArUpdatePoint(const T_DjiOpenArPointArray* entry);
|
||||
|
||||
/**
|
||||
* @brief Delete the ar point
|
||||
* @param metaData: the information for Ar point.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArDeletePoint(const T_DjiOpenArDeletePointEntry* entry);
|
||||
|
||||
/**
|
||||
* @brief Clear the ar point
|
||||
* @param metaData: the resource id for Ar point.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArClearPoint(uint32_t resource_id);
|
||||
|
||||
/**
|
||||
* @brief Set the ar line
|
||||
* @param metaData: the ar line information for setting.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArSetLine(const T_DjiOpenArLine* entry);
|
||||
|
||||
/**
|
||||
* @brief Update the ar line
|
||||
* @param metaData: The ar line information
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArUpdateLine(const T_DjiOpenArLine* entry);
|
||||
|
||||
/**
|
||||
* @brief Delete the ar line
|
||||
* @param metaData: The ar line entry for delete
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArDeleteLine(const T_DjiOpenArDeleteLineEntry* entry, uint32_t entry_len);
|
||||
|
||||
/**
|
||||
* @brief Clear the ar line.
|
||||
* @param metaData: The ar line information for clear.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArClearLine();
|
||||
|
||||
/**
|
||||
* @brief Set the ar polygon.
|
||||
* @param metaData: The ar polygon information for setting.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArSetPolygon(const T_DjiOpenArPolygon* entry);
|
||||
|
||||
/**
|
||||
* @brief Update the ar polygon.
|
||||
* @param metaData: The ar polygon information for update.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArUpdatePolygon(const T_DjiOpenArPolygon* entry);
|
||||
|
||||
/**
|
||||
* @brief Delete the ar polygon.
|
||||
* @param metaData: The polygon entry information for delete.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArDeletePolygon(const T_DjiOpenArDeletePolygonEntry* entry, uint32_t entry_len);
|
||||
|
||||
/**
|
||||
* @brief Clear the ar polygon.
|
||||
* @param metaData: none
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArClearPolygon();
|
||||
|
||||
/**
|
||||
* @brief Set the ar circle.
|
||||
* @param metaData: The ar circle information for setting.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArSetCircle(const T_DjiOpenArCircle* entry);
|
||||
|
||||
/**
|
||||
* @brief Update the ar circle.
|
||||
* @param metaData: The ar circle information for update.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArUpdateCircle(const T_DjiOpenArCircle* entry);
|
||||
|
||||
/**
|
||||
* @brief Delete the ar circle.
|
||||
* @param metaData: The ar circle information for delete.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArDeleteCircle(const T_DjiOpenArDeleteCircleEntry* entry, uint32_t entry_len);
|
||||
|
||||
/**
|
||||
* @brief Clear the ar circle.
|
||||
* @param metaData: The ar circle information for clear.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArClearCircle();
|
||||
|
||||
/**
|
||||
* @brief Set the pivot axis.
|
||||
* @param metaData: The pivot axis information for setting.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArSetPivotAxis(const T_DjiOpenArPivotAxis* entry);
|
||||
|
||||
/**
|
||||
* @brief Update the pivot axis.
|
||||
* @param metaData: The pivot axis information for update.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArUpdatePivotAxis(const T_DjiOpenArPivotAxis* entry);
|
||||
|
||||
/**
|
||||
* @brief Delete the pivot axis.
|
||||
* @param metaData: The pivot axis information for delete.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArDeletePivotAxis(const T_DjiOpenArDeletePovixAxisEntry* entry, uint32_t entry_len);
|
||||
|
||||
/**
|
||||
* @brief Clear the pivot axis.
|
||||
* @param metaData: none
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArClearPivotAxis();
|
||||
|
||||
/**
|
||||
* @brief Once entering this callback it is necessary to reflesh all AR drawings.
|
||||
* @param metaData: none
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
typedef void (*DjiLiveview_ArRefleshAllCallback)(void);
|
||||
|
||||
/**
|
||||
* @brief Register the ar refresh function.
|
||||
* @param metaData: The ar reflesh callback function.
|
||||
* @note This interface support on DJI manifold3.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiLiveview_ArRegRefleshAllCallback(DjiLiveview_ArRefleshAllCallback callback);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // DJI_OPEN_AR_H
|
||||
@ -173,6 +173,8 @@ typedef struct {
|
||||
bool isShootingIntervalStart; /*!< Specifies if the camera is in interval shooting start status. This parameter is boolean type. */
|
||||
uint16_t currentPhotoShootingIntervalTimeInSeconds; /*!< Specifies the current interval shoot countdown time, the value is decreasing,
|
||||
* when the value equals to zero trigger the interval take photo, uint:s. */
|
||||
uint16_t currentPhotoShootingIntervalTimeInMs; /*!< Specifies the current interval shoot countdown time of millisecond part, the value is decreasing,
|
||||
* when the value equals to zero trigger the interval take photo, uint:ms. */
|
||||
uint16_t currentPhotoShootingIntervalCount; /*!< Specifies the current interval photo count, the value is decreasing step by one from
|
||||
* the setted count when interval taking photo */
|
||||
bool isRecording; /*!< Specifies if the camera is in recording status. This parameter is boolean type. */
|
||||
@ -841,7 +843,7 @@ T_DjiReturnCode DjiPayloadCamera_RegMediaDownloadPlaybackHandler(const T_DjiCame
|
||||
* @param len: length of data to be sent via data stream, and it must be less than or equal to 65000, unit: byte.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPayloadCamera_SendVideoStream(const uint8_t *data, uint16_t len);
|
||||
T_DjiReturnCode DjiPayloadCamera_SendVideoStream(const uint8_t *data, uint32_t len);
|
||||
|
||||
/**
|
||||
* @brief Get data transmission state of "videoStream" channel. User can use the state as base for controlling data
|
||||
|
||||
@ -39,6 +39,8 @@ extern "C" {
|
||||
#define DJI_PERCEPTION_INTRINSICS_PARAM_ARRAY_NUM 9
|
||||
#define DJI_PERCEPTION_ROTATION_PARAM_ARRAY_NUM 9
|
||||
#define DJI_PERCEPTION_TRANSLATION_PARAM_ARRAY_NUM 3
|
||||
#define DJI_PTS_NUM_PER_PKG 96
|
||||
#define DJI_LIDAR_PKG_BUFFER_NUM 564
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/**
|
||||
@ -71,6 +73,19 @@ typedef enum {
|
||||
RECTIFY_RIGHT_RIGHT = 26
|
||||
} E_DjiPerceptionCameraPosition;
|
||||
|
||||
/**
|
||||
* @bref Perception radar design location
|
||||
*/
|
||||
typedef enum {
|
||||
RADAR_POSITION_LEFT = 0,
|
||||
RADAR_POSITION_RIGHT = 1,
|
||||
RADAR_POSITION_DOWN =2,
|
||||
RADAR_POSITION_UP = 3,
|
||||
RADAR_POSITION_FRONT = 4,
|
||||
RADAR_POSITION_BACK =5,
|
||||
MAX_RADAR_NUM = 6,
|
||||
}E_DjiPerceptionRadarPosition;
|
||||
|
||||
#pragma pack(1)
|
||||
/**
|
||||
* @bref Perception camera ram image info
|
||||
@ -114,14 +129,217 @@ typedef struct {
|
||||
uint32_t directionNum;
|
||||
T_DjiPerceptionCameraParameters cameraParameters[IMAGE_MAX_DIRECTION_NUM];
|
||||
} T_DjiPerceptionCameraParametersPacket;
|
||||
|
||||
/**
|
||||
* @bref Perception Lidar data point info
|
||||
*/
|
||||
typedef struct{
|
||||
float x; /*!< unit: meters */
|
||||
float y; /*!< unit: meters */
|
||||
float z; /*!< unit: meters */
|
||||
uint8_t intensity;
|
||||
uint8_t label; /*!< Noise filtering results (0: obj; 1: noise; 2: unknow; 3: not_retuen ) */
|
||||
} T_DJIPerceptionLidarPoint;
|
||||
|
||||
/**
|
||||
* @bref Perception Lidar data header of each pkg
|
||||
*/
|
||||
typedef struct{
|
||||
uint16_t timeInterval; /*!< The point cloud sampling time (in 0.1us) */
|
||||
uint16_t dotNum; /*!< Current packet data field contains the number of points This field is not valid for non-repeat scans*/
|
||||
uint8_t dataType; /** dataType
|
||||
*
|
||||
* Bit Position (7-4) | Field Name | Description | Remarks
|
||||
* ------------------ | ------------ | -------------------- | -------------------------------------------------
|
||||
* 4-7 | echo_mode | Echo Mode | 0: Single echo mode
|
||||
* | | | 1: Dual echo mode
|
||||
* | | | 2: Triple echo mode
|
||||
* | | | 3: Quadruple echo mode
|
||||
* | | | 4: Quintuple echo mode
|
||||
*
|
||||
* Bit Position (3-0) | Field Name | Description | Remarks
|
||||
* ------------------ | ------------ | -------------------- | -------------------------------------------------
|
||||
* 0-3 | data_type | Data Type | 40: IMU Data
|
||||
* | | | 1: Point cloud data (rectangular, 32-bit)
|
||||
* | | | 2: Point cloud data (rectangular, 16-bit default)
|
||||
* | | | 3: Point cloud data (spherical)
|
||||
* | | | 4: Point cloud data (rectangular, 20-bit, in use)
|
||||
*/
|
||||
uint8_t timeType; /** timeType
|
||||
* Timestamp Type | Sync Source Type | Data Format | Description
|
||||
* -------------- | ------------------- | ------------- | -------------------------------------------------
|
||||
* 0 | No sync source, | uint64_t | Timestamp is radar uptime, unit: ns
|
||||
* | | |
|
||||
* 1 | gPTP/PTP sync, | uint64_t | Timestamp is master clock source time, unit: ns
|
||||
* | | |
|
||||
* 2 | PPS + ns time sync | uint64_t | Unit: ns
|
||||
* | | |
|
||||
* 3 | PPS + UTC | uint64_t | UTC format is:
|
||||
* | | struct | struct {
|
||||
* | | | uint8_t year;
|
||||
* | | | uint8_t mon;
|
||||
* | | | uint8_t day;
|
||||
* | | | uint8_t hour;
|
||||
* | | | uint32_t us_offset;
|
||||
* | | | };
|
||||
*/
|
||||
uint64_t timeStamp;
|
||||
}T_DJIPerceptionLidarDataHeader;
|
||||
|
||||
/**
|
||||
* @bref Perception Lidar data pkg
|
||||
*/
|
||||
typedef struct{
|
||||
T_DJIPerceptionLidarDataHeader header;
|
||||
T_DJIPerceptionLidarPoint points[DJI_PTS_NUM_PER_PKG];
|
||||
}T_DjiPerceptionLidarDecodePkg;
|
||||
|
||||
/**
|
||||
* @bref Perception Lidar data frame
|
||||
*/
|
||||
typedef struct{
|
||||
uint64_t timeStampNs; /*!< Timestamp of the first point of each packet */
|
||||
uint32_t frameCnt; /*!< in increasing order from zero */
|
||||
uint16_t pkgNum; /*!< Number of valid pkgs per frame */
|
||||
T_DjiPerceptionLidarDecodePkg pkgs[DJI_LIDAR_PKG_BUFFER_NUM];
|
||||
uint32_t poseTimeMs;
|
||||
uint16_t naviFlag; /** naviFlag:
|
||||
* Bit Position | Field Name | Description | Remarks
|
||||
* ------------ | ---------- | ------------------------------------------------ | -----------------------------------
|
||||
* 0 | vel_x | Horizontal x-axis velocity valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 1 | vel_y | Horizontal y-axis velocity valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 2 | vel_z | Vertical velocity valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 3 | pos_x | Horizontal x-axis position valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 4 | pos_y | Horizontal y-axis position valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 5 | pos_z | Vertical position valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 6 | dwn_vz | Ground speed valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 7 | dwn_pz | Ground elevation valid bit (1 valid) | 1 - valid, 0 - invalid
|
||||
* 8 | rtk_pxy | RTK horizontal valid flag (1 valid) | 1 - valid, 0 - invalid
|
||||
* 9 | rtk_pz | RTK vertical valid flag (1 valid) | 1 - valid, 0 - invalid
|
||||
* 10 | gns_ll | GPS horizontal valid flag (1 valid) | 1 - valid, vertical direction always invalid
|
||||
* 11 | fg_ok | FG estimate OK flag (1 valid) | 1 - valid, 0 - invalid
|
||||
* 12-15 | fg_st | FG mode (4 bits) | Modes:
|
||||
* | | | 0 - Random initialization
|
||||
* | | | 1 - Initialization with poor compass
|
||||
* | | | 2 - Initialization with good compass
|
||||
* | | | 3 - Magnetic inclination compensation
|
||||
* | | | 4 - Compass fix during takeoff
|
||||
* | | | 5 - Compass fix in the air
|
||||
* | | | 6 - Compass calibration fix
|
||||
* | | | 7 - Accelerometer alignment
|
||||
* | | | 8 - Speed alignment
|
||||
* | | | 9 - RTK heading alignment
|
||||
*/
|
||||
float naviPos[3]; /*!< UAV IMU to navigation coordinate system translation vector (xyz) */
|
||||
float naviQuat[4]; /*!< Quaternions from UAV IMU to navigation coordinate system */
|
||||
}T_DjiLidarFrame;
|
||||
|
||||
/**
|
||||
* @bref Radar data frame header
|
||||
*/
|
||||
typedef struct {
|
||||
uint16_t dataLen;
|
||||
uint8_t curPack; /*!< The current packet number, in the range of [1, pack_num]. */
|
||||
uint8_t packNum; /*!< Total number of current circle packets, starting from 1. */
|
||||
} T_DjiRadarDataHeader;
|
||||
|
||||
/**
|
||||
* @bref Radar information structure
|
||||
*/
|
||||
typedef struct {
|
||||
uint64_t velocity :16; /**
|
||||
* Calculating the actual velocity:
|
||||
*
|
||||
* Actual velocity (m/s) = (Velocity - 32767) / 100
|
||||
*
|
||||
* Interpreting the results:
|
||||
* - If the result is > 0, it indicates that the object is moving closer to the target.
|
||||
* - If the result is < 0, it indicates that the object is moving away from the target.
|
||||
*/
|
||||
uint64_t snr :7; /*!< target SNR, in db, ranging from 0 to 127, with 0 being the null point or no echo point
|
||||
(base_noise calculation base_noise = energy / snr) */
|
||||
uint64_t beamAngle:10; /**
|
||||
* Beam emission angle value:
|
||||
* - Unit: 0.01 degrees
|
||||
* - Stored range: 0~1023
|
||||
* - Actual value range: [-45°, 45°]
|
||||
*
|
||||
* Conversion method:
|
||||
* - Divide stored value x by 10
|
||||
* - If x ≤ 450, the angle remains unchanged
|
||||
* - If x > 450, the angle is adjusted by subtracting 90
|
||||
*
|
||||
* Examples:
|
||||
* - Stored value of 449 yields an angle of 44.9° (449/10 = 44.9°)
|
||||
* - Stored value of 451 yields an angle of -44.9° (451/10 - 90 = -44.9°)
|
||||
* invalid in M400
|
||||
*/
|
||||
|
||||
uint64_t radarType:3; /*!< Radar numbe,is invalid in M400*/
|
||||
|
||||
uint64_t clitterFlag:1; /*!< Flag for clutter point in planar radar: 1 indicates a clutter point, 0 indicates a valid point */
|
||||
|
||||
uint64_t reserved :27;
|
||||
} T_DjiRadarBaseInfo;
|
||||
|
||||
/**
|
||||
* @bref The single point data structure of millimeter wave radar
|
||||
*/
|
||||
typedef struct {
|
||||
uint16_t azimuth; /*!
|
||||
* Target azimuth in radar coordinate system:
|
||||
* - Unit: 0.001 radian
|
||||
* - Value range: (0 to 2π) / 0.001
|
||||
* - Calculation method (azimuth/1000 - 2π)
|
||||
*/
|
||||
uint16_t elevation; /*!
|
||||
* Target pitch angle in radar coordinate system:
|
||||
* - Unit: 0.001 radian
|
||||
* - Value range: (0 to 2π) / 0.001
|
||||
* - Calculation method (elevation/1000 - 2π)
|
||||
*/
|
||||
uint16_t radius; /*!
|
||||
* Target radial distance in radar coordinate system:
|
||||
* - Unit: 0.01 meters
|
||||
* - Value range: 0 to 65553 (in steps of 0.01 meters)
|
||||
*/
|
||||
uint16_t ene; /*!
|
||||
* Radar target energy
|
||||
* - Actual value: energy / 100
|
||||
* - invalid in M400
|
||||
*/
|
||||
T_DjiRadarBaseInfo base_info;
|
||||
}T_DjiRadarCloudUnit;
|
||||
|
||||
/**
|
||||
* @bref Perception Radar data frame
|
||||
*/
|
||||
typedef struct {
|
||||
T_DjiRadarDataHeader headInfo;
|
||||
T_DjiRadarCloudUnit data[1];
|
||||
} T_DjiRadarDataFrame;
|
||||
|
||||
#pragma pack()
|
||||
|
||||
/**
|
||||
* @bref Callback type to receive stereo camera image
|
||||
* @note It is not recommended to perform blocking operations in the callback, as it may lead to data loss.
|
||||
*/
|
||||
typedef void(*DjiPerceptionImageCallback)(T_DjiPerceptionImageInfo imageInfo, uint8_t *imageRawBuffer,
|
||||
uint32_t bufferLen);
|
||||
|
||||
/**
|
||||
* @bref Callback type to receive radar data
|
||||
* @note It is not recommended to perform blocking operations in the callback, as it may lead to data loss.
|
||||
*/
|
||||
typedef void(*DjiPerceptionRadarCallback)(E_DjiPerceptionRadarPosition radarPosition, uint8_t *radarDataBuffer,
|
||||
uint32_t bufferLen);
|
||||
/**
|
||||
* @bref Callback type to process Lidar data
|
||||
* @note It is not recommended to perform blocking operations in the callback, as it may lead to data loss.
|
||||
*/
|
||||
typedef void(*DjiPerceptionLidarDataCallback)(uint8_t* lidarDataBuffer, uint32_t bufferLen);
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Initialize the perception module.
|
||||
@ -147,18 +365,44 @@ T_DjiReturnCode DjiPerception_SubscribePerceptionImage(E_DjiPerceptionDirection
|
||||
|
||||
/**
|
||||
* @brief Unsubscribe the raw image of both stereo cameras in the same direction.
|
||||
* @param direction: direction to specify the direction of the subscription. Ref to E_DjiPerceptionDirection
|
||||
* @param direction: direction to specify the direction of the subscription. Ref to E_DjiPerceptionDirection.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPerception_UnsubscribePerceptionImage(E_DjiPerceptionDirection direction);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get the internal and external parameters of all stereo cameras.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPerception_GetStereoCameraParameters(T_DjiPerceptionCameraParametersPacket *packet);
|
||||
|
||||
/**
|
||||
* @brief Subscribe the lidar data.
|
||||
* @param callback: callback to observer the radar data.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPerception_SubscribeLidarData(DjiPerceptionLidarDataCallback callback);
|
||||
|
||||
/**
|
||||
* @brief Unsubscribe the lidar data.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPerception_UnsubscribeLidarData(void);
|
||||
|
||||
/**
|
||||
* @brief Subscribe the lidar data of the position.
|
||||
* @param position: position the radar monted
|
||||
* @param callback callback to observer the radar data.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPerception_SubscribeRadarData(E_DjiPerceptionRadarPosition position, DjiPerceptionRadarCallback callback);
|
||||
|
||||
/**
|
||||
* @brief Unsubscribe the lidar data of the position.
|
||||
* @param position: position the radar monted
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPerception_UnsubscribeRadarData(E_DjiPerceptionRadarPosition position);
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -109,6 +109,7 @@ typedef enum {
|
||||
typedef enum {
|
||||
DJI_HAL_USB_BULK_NUM_0 = 0,
|
||||
DJI_HAL_USB_BULK_NUM_1,
|
||||
DJI_HAL_USB_BULK_NUM_2,
|
||||
DJI_HAL_USB_BULK_NUM_MAX,
|
||||
} E_DjiHalUsbBulkNum;
|
||||
|
||||
@ -138,6 +139,11 @@ typedef struct {
|
||||
bool isDir;
|
||||
} T_DjiFileInfo;
|
||||
|
||||
typedef struct {
|
||||
uint16_t pid;
|
||||
uint16_t vid;
|
||||
} T_DjiHalUartDeviceInfo;
|
||||
|
||||
typedef struct {
|
||||
T_DjiReturnCode (*UartInit)(E_DjiHalUartNum uartNum, uint32_t baudRate, T_DjiUartHandle *uartHandle);
|
||||
|
||||
@ -148,6 +154,13 @@ typedef struct {
|
||||
T_DjiReturnCode (*UartReadData)(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen);
|
||||
|
||||
T_DjiReturnCode (*UartGetStatus)(E_DjiHalUartNum uartNum, T_DjiUartStatus *status);
|
||||
|
||||
/**
|
||||
* Get the device info of USB uart (virtual com or TTL-To-USB) which directly connected to UAV.
|
||||
* Use for SDK adapter type Eport V2 ribbon cable.
|
||||
* When using other types of interface, it is not necessary to implement this member function.
|
||||
*/
|
||||
T_DjiReturnCode (*UartGetDeviceInfo)(T_DjiHalUartDeviceInfo *deviceInfo);
|
||||
} T_DjiHalUartHandler;
|
||||
|
||||
typedef struct {
|
||||
|
||||
@ -45,6 +45,12 @@ typedef enum {
|
||||
DJI_POWER_MANAGEMENT_PIN_STATE_SET = 1, /*!< Specifies pin is in high level state. */
|
||||
} E_DjiPowerManagementPinState;
|
||||
|
||||
typedef enum {
|
||||
E_DJI_HIGH_POWER_VOLTAGE_13V6 = 0, /*!< Specifies pin is in 13.6V of voltage */
|
||||
E_DJI_HIGH_POWER_VOLTAGE_17V = 1, /*!< Specifies pin is in 17V of voltage */
|
||||
E_DJI_HIGH_POWER_VOLTAGE_24V = 2, /*!< Specifies pin is in 24V of voltage */
|
||||
} E_DjiHighPowerVoltage;
|
||||
|
||||
/**
|
||||
* @brief Prototype of callback function used to set level of high power application pin.
|
||||
* @param pinState: level state of pin to be set.
|
||||
@ -87,6 +93,17 @@ T_DjiReturnCode DjiPowerManagement_DeInit(void);
|
||||
*/
|
||||
T_DjiReturnCode DjiPowerManagement_ApplyHighPowerSync(void);
|
||||
|
||||
/**
|
||||
* @brief Apply high power from aircraft in blocking mode.
|
||||
* @details Before applying, user should register callback function used to set level state of high power application
|
||||
* pin using DjiPowerManagement_RegWriteHighPowerApplyPinCallback() function. After applying high power, power pin of
|
||||
* DJI adapter will output high power based predetermined specification.
|
||||
* @note Max execution time of this function is slightly larger than 600ms.
|
||||
* @param voltage: The voltage value will be applied to the VCC pin.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiPowerManagement_ApplyHighPowerSyncV2(E_DjiHighPowerVoltage voltage);
|
||||
|
||||
/**
|
||||
* @brief Register callback function used to set level state of high power application pin. Must be called before
|
||||
* applying high power.
|
||||
@ -108,6 +125,15 @@ T_DjiReturnCode DjiPowerManagement_RegWriteHighPowerApplyPinCallback(DjiWriteHig
|
||||
*/
|
||||
T_DjiReturnCode DjiPowerManagement_RegPowerOffNotificationCallback(DjiPowerOffNotificationCallback callback);
|
||||
|
||||
/**
|
||||
* @brief manifold3 outputs high voltage to external devices
|
||||
* @param stat: true: output high voltage, false: output low voltage
|
||||
* @return Execution result.
|
||||
* @note The gpio12 of manifold3 should be pulled down before requesting a high voltage output.
|
||||
* @note This interface support on DJI manifold3.
|
||||
*/
|
||||
T_DjiReturnCode DjiPowerManagement_OutputHighPower(bool stat);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
77
psdk_lib/include/dji_tethered_battery.h
Normal file
77
psdk_lib/include/dji_tethered_battery.h
Normal file
@ -0,0 +1,77 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_tethered_battery.h
|
||||
* @brief This is the header file for "dji_tethered_battery.c", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2024 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef DJI_TETHERED_BATTERY_H
|
||||
#define DJI_TETHERED_BATTERY_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_typedef.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Tether line status.
|
||||
*/
|
||||
typedef struct {
|
||||
dji_f32_t totalLength; /*!< total length of tether line, range: 0-300, unit: meters. */
|
||||
dji_f32_t usedLength; /*!< used length of tether line, range: 0-300, unit: meters.
|
||||
This value must be less than or equal to the total length of tether line. */
|
||||
} T_DjiTetherLineStatus;
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Initialise tethered battery module
|
||||
* @note User should call this function before using tethered battery features.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiTetheredBattery_Init(void);
|
||||
|
||||
/**
|
||||
* @brief DeInitialize tethered battery module.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiTetheredBattery_DeInit(void);
|
||||
|
||||
/**
|
||||
* @brief Push the real-time tether line length to the Pilot2 for display.
|
||||
* @note It is recommended that the push frequency does not exceed the data update frequency. The maximum push
|
||||
* frequency should not exceed 10Hz.
|
||||
* @param tetherLineStatus: the tether line status.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiTetheredBattery_PushTetherLineStatus(T_DjiTetherLineStatus tetherLineStatus);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // DJI_TETHERED_BATTERY_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
@ -44,6 +44,7 @@ extern "C" {
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
#define DJI_PI (3.14159265358979323846f)
|
||||
#define DJI_FILE_NAME_SIZE_MAX 256
|
||||
#define DJI_FILE_MD5_LENGTH 16
|
||||
#define DJI_FILE_PATH_SIZE_MAX (DJI_FILE_NAME_SIZE_MAX + 256)
|
||||
#define DJI_IP_ADDR_STR_SIZE_MAX 16
|
||||
#define DJI_MD5_BUFFER_LEN 16
|
||||
@ -58,6 +59,12 @@ extern "C" {
|
||||
(((((uint32_t)(subscriptionModule)) << (DJI_SUBSCRIPTION_MODULE_INDEX_OFFSET)) & (DJI_SUBSCRIPTION_MODULE_INDEX_MASK)) | \
|
||||
((((uint32_t)(topicCode)) << (DJI_SUBSCRIPTION_TOPIC_CODE_OFFSET)) & (DJI_SUBSCRIPTION_TOPIC_CODE_MASK)))
|
||||
|
||||
#define DJI_DATA_SUBSCRIPTION_TOPIC_GET_MODULE(topic) \
|
||||
((uint32_t)((topic & DJI_SUBSCRIPTION_MODULE_INDEX_MASK) >> DJI_SUBSCRIPTION_MODULE_INDEX_OFFSET))
|
||||
|
||||
#define DJI_DATA_SUBSCRIPTION_TOPIC_GET_CODE(topic) \
|
||||
((uint32_t)((topic & DJI_SUBSCRIPTION_TOPIC_CODE_MASK) >> DJI_SUBSCRIPTION_TOPIC_CODE_OFFSET))
|
||||
|
||||
/**
|
||||
* @brief Type define double as dji_f64_t.
|
||||
*/
|
||||
@ -77,6 +84,8 @@ typedef enum {
|
||||
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_PORT_V2 = 4,
|
||||
DJI_MOUNT_POSITION_TYPE_MANIFOLD3_ONBOARD = 5,
|
||||
} E_DjiMountPositionType;
|
||||
|
||||
typedef enum {
|
||||
@ -84,8 +93,15 @@ typedef enum {
|
||||
DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1 = 1,
|
||||
DJI_MOUNT_POSITION_PAYLOAD_PORT_NO2 = 2,
|
||||
DJI_MOUNT_POSITION_PAYLOAD_PORT_NO3 = 3,
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT = 4,
|
||||
DJI_MOUNT_POSITION_EXTENSION_LITE_PORT = 5,
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO1 = DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1,
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO2 = DJI_MOUNT_POSITION_PAYLOAD_PORT_NO2,
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO3 = DJI_MOUNT_POSITION_PAYLOAD_PORT_NO3,
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO4 = 4,
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO5 = 5,
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO6 = 6,
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO7 = 7,
|
||||
DJI_MOUNT_POSITION_EXTENSION_PORT,
|
||||
DJI_MOUNT_POSITION_EXTENSION_LITE_PORT,
|
||||
} E_DjiMountPosition;
|
||||
|
||||
typedef enum {
|
||||
@ -98,7 +114,8 @@ typedef enum {
|
||||
DJI_AIRCRAFT_SERIES_M3D = 6,
|
||||
DJI_AIRCRAFT_SERIES_FC30 = 7,
|
||||
DJI_AIRCRAFT_SERIES_M4 = 8,
|
||||
DJI_AIRCRAFT_SERIES_M4D = 9,
|
||||
DJI_AIRCRAFT_SERIES_M4D = 9,
|
||||
DJI_AIRCRAFT_SERIES_M400 = 10,
|
||||
} E_DjiAircraftSeries;
|
||||
|
||||
typedef enum {
|
||||
@ -115,10 +132,11 @@ typedef enum {
|
||||
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. */
|
||||
DJI_AIRCRAFT_TYPE_M4T = 99, /*!< Aircraft type is Mavic 4T. */
|
||||
DJI_AIRCRAFT_TYPE_M4E = 990, /*!< Aircraft type is Mavic 4E. */
|
||||
DJI_AIRCRAFT_TYPE_M4T = 99, /*!< Aircraft type is Matrice 4T. */
|
||||
DJI_AIRCRAFT_TYPE_M4E = 990, /*!< Aircraft type is Matrice 4E. */
|
||||
DJI_AIRCRAFT_TYPE_M4TD = 100, /*!< Aircraft type is Matrice 4TD. */
|
||||
DJI_AIRCRAFT_TYPE_M4D = 1000, /*!< Aircraft type is Matrice 4D. */
|
||||
DJI_AIRCRAFT_TYPE_M400 = 103, /*!< Aircraft type is Matrice 400. */
|
||||
} E_DjiAircraftType;
|
||||
|
||||
/**
|
||||
@ -259,6 +277,8 @@ typedef enum {
|
||||
DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 = 1, /*!< SDK adapter type is Skyport V2. */
|
||||
DJI_SDK_ADAPTER_TYPE_XPORT = 2, /*!< SDK adapter type is X-Port. */
|
||||
DJI_SDK_ADAPTER_TYPE_NONE = 3, /*!< don't have any adapter outside */
|
||||
DJI_SDK_ADAPTER_TYPE_SKYPORT_V3 = 4, /*!< SDK adapter type is Skyport V3 */
|
||||
DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE = 5, /*!< SDK adapter type is Eport V2 ribbon cable */
|
||||
} E_DjiSdkAdapterType;
|
||||
|
||||
typedef enum {
|
||||
@ -266,6 +286,13 @@ typedef enum {
|
||||
DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO1,
|
||||
DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO2,
|
||||
DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO3,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO1 = DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO1,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO2 = DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO2,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO3 = DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO3,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO4,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO5,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO6,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT_V2_NO7,
|
||||
DJI_CHANNEL_ADDRESS_EXTENSION_PORT,
|
||||
DJI_CHANNEL_ADDRESS_MASTER_RC_APP,
|
||||
DJI_CHANNEL_ADDRESS_SLAVE_RC_APP,
|
||||
@ -288,6 +315,7 @@ typedef struct {
|
||||
uint8_t captureCount; /*!< Specifies the total capture count of interval settings.
|
||||
* 0: reserved, 1-254: specific number, 255: continuous capture until stopped. */
|
||||
uint16_t timeIntervalSeconds; /*!< Specifies the interval time between two captures, unit: s*/
|
||||
uint16_t timeIntervalMilliseconds; /*!< Specifies the interval time between two captures, unit: ms*/
|
||||
} T_DjiCameraPhotoTimeIntervalSettings;
|
||||
|
||||
/**
|
||||
|
||||
@ -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 11 /*!< DJI SDK minor version num, when add functionality in a backwards compatible manner changes. Range from 0 to 99. */
|
||||
#define DJI_VERSION_MODIFY 1 /*!< DJI SDK modify version num, when have backwards compatible bug fixes changes. Range from 0 to 99. */
|
||||
#define DJI_VERSION_MINOR 12 /*!< 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 2212 /*!< DJI SDK version build info, when jenkins trigger build changes. Range from 0 to 65535. */
|
||||
#define DJI_VERSION_BUILD 2254 /*!< DJI SDK version build info, when jenkins trigger build changes. Range from 0 to 65535. */
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
|
||||
308
psdk_lib/include/dji_widget_manager.h
Normal file
308
psdk_lib/include/dji_widget_manager.h
Normal file
@ -0,0 +1,308 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_widget_states_manager.h
|
||||
* @version V1.0.0
|
||||
* @date 2020/11/26
|
||||
* @brief This is the header file for "dji_widget_manager.h", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef DJI_WIDGET_STATES_MANNAGER_H
|
||||
#define DJI_WIDGET_STATES_MANNAGER_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_typedef.h"
|
||||
#include "dji_widget.h"
|
||||
#include "dji_camera_manager.h"
|
||||
// #include "downloader/dji_download_file.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
#define WIDGET_MANAGER_MAX_FILE_NAME_LEN 32
|
||||
#define WIDGET_MANAGER_MAX_FILE_PATH_LEN 128
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Speaker system states.
|
||||
*/
|
||||
typedef enum {
|
||||
DJI_WIDGET_MGR_SPEAKER_SYSTEM_STATE_IDEL = 0,
|
||||
DJI_WIDGET_MGR_SPEAKER_SYSTEM_STATE_IN_TRANSMISSION = 1,
|
||||
DJI_WIDGET_MGR_SPEAKER_SYSTEM_STATE_PLAYING = 2,
|
||||
DJI_WIDGET_MGR_SPEAKER_SYSTEM_STATE_EXCEPTION = 3,
|
||||
DJI_WIDGET_MGR_SPEAKER_SYSTEM_STATE_IN_TTS_CONVERSION = 4,
|
||||
} E_DjiWidgetManagerSpeakerStates;
|
||||
|
||||
/**
|
||||
* @brief Speaker parameters.
|
||||
*/
|
||||
typedef enum {
|
||||
DJI_WIDGET_MGR_SPEAKER_PARAM_WORK_MODE = 0, /*!< The working mode fo the speaker */
|
||||
DJI_WIDGET_MGR_SPEAKER_PARAM_PALY_ACTION = 1, /*!< The playing action of the speaker */
|
||||
DJI_WIDGET_MGR_SPEAKER_PARAM_VOLUME = 2, /*!< The volume action of the speaker */
|
||||
DJI_WIDGET_MGR_SPEAKER_PARAM_PLAY_MODE = 3, /*!< The playing mode of the speaker */
|
||||
DJI_WIDGET_MGR_SPEAKER_PARAM_PLAY_FILE_NAME = 4, /*!<The name of the file to be played */
|
||||
} E_DjiWidgetManagerSpeakerPram;
|
||||
|
||||
/**
|
||||
* @brief Speaker audio bitrate
|
||||
*/
|
||||
typedef enum {
|
||||
DJI_SPEAKER_WIDGET_AUDIO_DECODE_BITRATE_8000 = 1,
|
||||
DJI_SPEAKER_WIDGET_AUDIO_DECODE_BITRATE_16000 = 2,
|
||||
DJI_SPEAKER_WIDGET_AUDIO_DECODE_BITRATE_24000 = 3,
|
||||
DJI_SPEAKER_WIDGET_AUDIO_DECODE_BITRATE_32000 = 4,
|
||||
DJI_SPEAKER_WIDGET_AUDIO_DECODE_BITRATE_48000 = 5,
|
||||
DJI_SPEAKER_WIDGET_AUDIO_DECODE_BITRATE_64000 = 6,
|
||||
} E_DjiWidgetManagerSpeakerAudoBitrate;
|
||||
|
||||
/**
|
||||
* @brief The type of audio file
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
DJI_SPEAKER_WIDGET_FILE_TYPE_TTS_TXT = 0,
|
||||
DJI_SPEAKER_WIDGET_FILE_TYPE_OPUS = 1,
|
||||
DJI_SPEAKER_WIDGET_FILE_TYPE_WAV = 2,
|
||||
} E_DjiWidgetManagerSpeakerFileType;
|
||||
|
||||
/**
|
||||
* @brief The states of widget.
|
||||
*/
|
||||
typedef struct{
|
||||
E_DjiWidgetType widgetType; /*!< The type fo the widget */
|
||||
uint8_t widgetIndex; /*!< The index fo the widget */
|
||||
int32_t widgetValue; /*!< The value fo the widget */
|
||||
} T_DjiWidgetStates;
|
||||
|
||||
/**
|
||||
* @brief The information of audio file.
|
||||
*/
|
||||
typedef struct{
|
||||
E_DjiWidgetManagerSpeakerFileType fileType; /*!< The type fo the audio file */
|
||||
E_DjiWidgetManagerSpeakerAudoBitrate fileBitrate; /*!< The bitrate fo the audio file */
|
||||
uint8_t uuid[WIDGET_MANAGER_MAX_FILE_NAME_LEN]; /*!< The uuid fo the audio file */
|
||||
uint8_t fileName[WIDGET_MANAGER_MAX_FILE_NAME_LEN]; /*!< The fileName fo the audio file */
|
||||
uint8_t filePath[WIDGET_MANAGER_MAX_FILE_PATH_LEN]; /*!< The absolute path to the audio file */
|
||||
} T_DjiSpeakerAudioFileInfo;
|
||||
|
||||
/**
|
||||
* @brief The states of the speaker's widget
|
||||
*/
|
||||
typedef struct {
|
||||
E_DjiWidgetSpeakerWorkMode workMode; /*!< The working mode of the speaker */
|
||||
E_DjiWidgetSpeakerPlayMode playMode; /*!< The playing mode of the speaker */
|
||||
uint8_t playVloume; /*!< The vloume of the speaker */
|
||||
E_DjiWidgetManagerSpeakerStates systemStates; /*!< The system states of the speaker */
|
||||
uint8_t playFileUuid[WIDGET_MANAGER_MAX_FILE_NAME_LEN]; /*!< The uuid of the playing file */
|
||||
uint8_t playFileName[WIDGET_MANAGER_MAX_FILE_NAME_LEN]; /*!< The name of the playing file */
|
||||
uint8_t playQuality; /*!< packet loss per second [0-255] mapped to 0%-100% */
|
||||
uint8_t actualVolume; /*!< The actual volume of the speaker */
|
||||
uint8_t limitVolumeOnTheGround; /*!< The limit volume when aircraft is on the ground */
|
||||
} T_DjiSpeakerWidgetStates;
|
||||
|
||||
/**
|
||||
* @brief Speaker parameters to be set
|
||||
*/
|
||||
typedef struct {
|
||||
E_DjiWidgetManagerSpeakerPram paramType; /*!< Type of speaker parameter to set */
|
||||
union {
|
||||
uint8_t value;
|
||||
uint8_t fileName[32];
|
||||
}data;
|
||||
} T_DjiSpeakerWidgetStatesParam;
|
||||
|
||||
/**
|
||||
* @brief Widget file information
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t fileSize;
|
||||
uint32_t fileIndex;
|
||||
char fileName[DJI_FILE_NAME_SIZE_MAX];
|
||||
} T_DjiWidgetManagerFileInfo;
|
||||
|
||||
/**
|
||||
* @brief The list of widget file information
|
||||
*/
|
||||
typedef struct{
|
||||
uint8_t totalCount;
|
||||
T_DjiWidgetManagerFileInfo *fileListInfo;
|
||||
} T_DjiWidgetManagerFileList;
|
||||
|
||||
/**
|
||||
* @brief Widget file download process information
|
||||
*/
|
||||
typedef struct {
|
||||
E_DjiDownloadFileEvent downloadFileEvent; /*!< Download Event Type */
|
||||
E_DjiMountPosition position; /*!< The position of the payload of the downloaded file */
|
||||
uint32_t fileIndex;
|
||||
uint32_t fileSize;
|
||||
dji_f32_t progressInPercent;
|
||||
} T_DjiDownloadWidgetFileInfo;
|
||||
|
||||
/**
|
||||
* @brief Type of callback function to receive widget states.
|
||||
* @param position: The position of the payload from which the widget states comes.
|
||||
* @param statesData: widgets states of widgets.
|
||||
* @param widgetNum: Number of widgets.
|
||||
* @note It is not recommended to perform blocking operations in the callback, as it may lead to data loss.
|
||||
* @return Execution result.
|
||||
*/
|
||||
typedef void (*RecvWidgetStatesCallback)(E_DjiMountPosition position, T_DjiWidgetStates *statesData, uint8_t widgetNum);
|
||||
|
||||
/**
|
||||
* @brief Type of callback function to receive speaker widget states.
|
||||
* @param position: The position of the speaker from which the widget states comes.
|
||||
* @param statesData: widgets states of speaker.
|
||||
* @note It is not recommended to perform blocking operations in the callback, as it may lead to data loss.
|
||||
* @return Execution result.
|
||||
*/
|
||||
typedef void (*RecvSpeakerStatesCallback)(E_DjiMountPosition position, T_DjiSpeakerWidgetStates *speakerStates);
|
||||
|
||||
/**
|
||||
* @brief Types of callback functions that handle downloading widget file data.
|
||||
* @param packetInfo: Widget file download process information.
|
||||
* @param data: Download raw data.
|
||||
* @param len: length of data.
|
||||
* @note It is not recommended to perform blocking operations in the callback, as it may lead to data loss.
|
||||
* @return Execution result.
|
||||
*/
|
||||
typedef T_DjiReturnCode (*DjiWidgetDownloadFileDataCallback)(T_DjiDownloadWidgetFileInfo packetInfo,
|
||||
const uint8_t *data,
|
||||
uint16_t dataLen);
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Initialize the widget manager module.
|
||||
* @note The interface initialization needs to be after DjiCore_Init.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_Init();
|
||||
|
||||
/**
|
||||
* @brief Denitialize the widget manager module.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_DeInit();
|
||||
|
||||
/**
|
||||
* @brief Subscribe to the widget states of a Payload.
|
||||
* @param position: the position of the target payload.
|
||||
* @param recvStatesCallback: the callback function to recv the widget states.
|
||||
* @note Use this interface to be notified when the states of the target payload's widget changes.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_SubscribePayloadWidgetStates(E_DjiMountPosition position,
|
||||
RecvWidgetStatesCallback recvStatesCallback);
|
||||
|
||||
/**
|
||||
* @brief Unsubscribe to the widget states of a Payload.
|
||||
* @param position: the position of the target payload.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_UnsubscribePayloadWidgetStates(E_DjiMountPosition position);
|
||||
|
||||
/**
|
||||
* @brief Set the widge state of the target payload.
|
||||
* @param position: the position of the target payload.
|
||||
* @param states: Widget parameters to be set.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_SetWidgetState(E_DjiMountPosition position, T_DjiWidgetStates states);
|
||||
|
||||
/**
|
||||
* @brief Subscribe to the widget states of a speaker.
|
||||
* @param position: the position of the target speaker.
|
||||
* @param recvStatesCallback: the callback function to recv the widget states.
|
||||
* @note Use this interface to be notified when the states of the target speaker's widget changes.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_SubscribeSpeakerStates(E_DjiMountPosition position,
|
||||
RecvSpeakerStatesCallback recvStatesCallback);
|
||||
|
||||
/**
|
||||
* @brief Unsubscribe to the widget states of a speaker.
|
||||
* @param position: the position of the target speaker.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_UnsubscribeSpeakerStates(E_DjiMountPosition position);
|
||||
|
||||
/**
|
||||
* @brief Set the widge state of the target speaker.
|
||||
* @param position: the position of the target payload.
|
||||
* @param states: Widget parameters to be set.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_SetSpeakertState(E_DjiMountPosition position,
|
||||
T_DjiSpeakerWidgetStatesParam *states);
|
||||
|
||||
/**
|
||||
* @brief Transferring audio files to speaker.
|
||||
* @param position: the position of the target speaker.
|
||||
* @param audioFileInfo: Audio file description information.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_SendSpeakerAudioData(E_DjiMountPosition position,
|
||||
T_DjiSpeakerAudioFileInfo *audioFileInfo);
|
||||
|
||||
/**
|
||||
* @brief Download the list of widget files for the target payload
|
||||
* @param position: the position of the target speaker.
|
||||
* @param fileList: Information on the list of files obtained from the download.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_WidgetDownloadFileList(E_DjiMountPosition position,
|
||||
T_DjiWidgetManagerFileList *fileList) ;
|
||||
|
||||
/**
|
||||
* @brief Registering callback functions for downloading widget files
|
||||
* @param position: The position of the target speaker.
|
||||
* @param recvFileCallback: The callback to receive the downloaded widget file.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_RegDownloadFileDataCallback(E_DjiMountPosition position,
|
||||
DjiWidgetDownloadFileDataCallback recvFileCallback);
|
||||
|
||||
/**
|
||||
* @brief Unregistering callback functions for downloading widget files.
|
||||
* @param position: The position of the target speaker.
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_UnRegDownloadFileDataCallback(E_DjiMountPosition position);
|
||||
|
||||
/**
|
||||
* @brief Download the corresponding widget file on the target payload according to the file index.
|
||||
* @param position: The position of the target speaker.
|
||||
* @param fileIndex: The index of the file that will be downloaded
|
||||
* @return Execution result.
|
||||
*/
|
||||
T_DjiReturnCode DjiWidgetManager_DownloadFileByIndex(E_DjiMountPosition position, uint32_t fileIndex);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // DJI_WIDGET_STATES_MANNAGER_H
|
||||
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
Binary file not shown.
Binary file not shown.
Binary file not shown.
BIN
psdk_lib/lib/armcc_cortex-m33/libpayload.lib
Normal file
BIN
psdk_lib/lib/armcc_cortex-m33/libpayload.lib
Normal file
Binary file not shown.
Binary file not shown.
Binary file not shown.
@ -109,18 +109,10 @@ void DjiUser_RunCameraManagerSample(void)
|
||||
<< "| Available position: |"
|
||||
<<
|
||||
endl;
|
||||
cout
|
||||
<< "| [1] Select gimbal mount position at NO.1 payload port |"
|
||||
<<
|
||||
endl;
|
||||
cout
|
||||
<< "| [2] Select gimbal mount position at NO.2 payload port |"
|
||||
<<
|
||||
endl;
|
||||
cout
|
||||
<< "| [3] Select gimbal mount position at NO.3 payload port |"
|
||||
<<
|
||||
endl;
|
||||
std::cout
|
||||
<< "| [1 ~ 4] Select camera mount position at NO.1~NO.4 |"
|
||||
<<
|
||||
std::endl;
|
||||
cout
|
||||
<< "| [q] Quit |"
|
||||
<<
|
||||
@ -134,7 +126,7 @@ void DjiUser_RunCameraManagerSample(void)
|
||||
|
||||
posNum = atoi(mountPositionStr.c_str());
|
||||
|
||||
if (posNum > 3 || posNum < 1) {
|
||||
if (posNum > 4 || posNum < 1) {
|
||||
USER_LOG_ERROR("Input mount position is invalid");
|
||||
continue;
|
||||
} else {
|
||||
|
||||
@ -84,6 +84,7 @@ static T_DjiFcSubscriptionControlDevice DjiUser_FlightControlGetValueOfControlDe
|
||||
static T_DjiFcSubscriptionSingleBatteryInfo DjiUser_FlightControlGetValueOfBattery1(void);
|
||||
static T_DjiFcSubscriptionSingleBatteryInfo DjiUser_FlightControlGetValueOfBattery2(void);
|
||||
static T_DjiReturnCode DjiUser_FlightControlUpdateConfig(void);
|
||||
static T_DjiReturnCode DjiUser_ShowCommandFlyingMenu(void);
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
@ -107,7 +108,9 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
return;
|
||||
}
|
||||
|
||||
osalHandler->TaskSleepMs(1000);
|
||||
osalHandler->TaskSleepMs(3000);
|
||||
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
|
||||
while (1) {
|
||||
osalHandler->TaskSleepMs(1);
|
||||
@ -119,7 +122,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = 0;
|
||||
s_flyingCommand.yaw = 0;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Front\r\n");
|
||||
break;
|
||||
case 'S':
|
||||
case 's':
|
||||
@ -128,7 +130,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = 0;
|
||||
s_flyingCommand.yaw = 0;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Near\r\n");
|
||||
break;
|
||||
case 'A':
|
||||
case 'a':
|
||||
@ -137,7 +138,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = 0;
|
||||
s_flyingCommand.yaw = 0;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Left\r\n");
|
||||
break;
|
||||
case 'D':
|
||||
case 'd':
|
||||
@ -146,7 +146,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = 0;
|
||||
s_flyingCommand.yaw = 0;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Right\r\n");
|
||||
break;
|
||||
case 'Q':
|
||||
case 'q':
|
||||
@ -155,7 +154,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = s_flyingSpeed;
|
||||
s_flyingCommand.yaw = 0;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Up\r\n");
|
||||
break;
|
||||
case 'E':
|
||||
case 'e':
|
||||
@ -164,7 +162,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = -s_flyingSpeed;
|
||||
s_flyingCommand.yaw = 0;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Down\r\n");
|
||||
break;
|
||||
case 'Z':
|
||||
case 'z':
|
||||
@ -173,7 +170,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = 0;
|
||||
s_flyingCommand.yaw = -30;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Yaw--\r\n");
|
||||
break;
|
||||
case 'C':
|
||||
case 'c':
|
||||
@ -182,96 +178,112 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = 0;
|
||||
s_flyingCommand.yaw = 30;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Yaw++\r\n");
|
||||
break;
|
||||
case 'R':
|
||||
case 'r':
|
||||
DjiFlightController_ObtainJoystickCtrlAuthority();
|
||||
DjiFlightController_StartTakeoff();
|
||||
USER_LOG_INFO(" - Take off\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'F':
|
||||
case 'f':
|
||||
DjiFlightController_StartForceLanding();
|
||||
USER_LOG_INFO(" - Force landing\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'H':
|
||||
case 'h':
|
||||
DjiFlightController_StartGoHome();
|
||||
USER_LOG_INFO(" - Start go home\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'Y':
|
||||
case 'y':
|
||||
DjiFlightController_CancelGoHome();
|
||||
USER_LOG_INFO(" - Cancel go home\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'G':
|
||||
case 'g':
|
||||
DjiFlightController_StartLanding();
|
||||
USER_LOG_INFO(" - Start landing\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'T':
|
||||
case 't':
|
||||
DjiFlightController_CancelLanding();
|
||||
USER_LOG_INFO(" - Cancel landing\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'V':
|
||||
case 'v':
|
||||
DjiFlightController_StartConfirmLanding();
|
||||
USER_LOG_INFO(" - Confirm landing\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'X':
|
||||
case 'x':
|
||||
s_homeLocation.longitude = (dji_f64_t) s_gpsPosition.x / 10000000;
|
||||
s_homeLocation.latitude = (dji_f64_t) s_gpsPosition.y / 10000000;
|
||||
DjiFlightController_SetHomeLocationUsingCurrentAircraftLocation();
|
||||
USER_LOG_INFO(" - Set home location\r\n");
|
||||
USER_LOG_INFO(" - Set home location (%.4f, %.4f)\r\n", s_homeLocation.longitude, s_homeLocation.latitude);
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'P':
|
||||
case 'p':
|
||||
DjiFlightController_EmergencyStopMotor(DJI_FLIGHT_CONTROLLER_ENABLE_EMERGENCY_STOP_MOTOR,
|
||||
(char *) "Test is ok");
|
||||
USER_LOG_INFO(" - Emergency stop motor\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'B':
|
||||
case 'b':
|
||||
DjiFlightController_TurnOnMotors();
|
||||
USER_LOG_INFO(" - Turn on motors\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'N':
|
||||
case 'n':
|
||||
DjiFlightController_TurnOffMotors();
|
||||
USER_LOG_INFO(" - Turn off motors\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'J':
|
||||
case 'j':
|
||||
DjiUser_FlightControlUpdateConfig();
|
||||
USER_LOG_INFO(" - Update config\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'I':
|
||||
case 'i':
|
||||
DjiFlightController_ArrestFlying();
|
||||
USER_LOG_INFO(" - Enable arrest flying\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'O':
|
||||
case 'o':
|
||||
DjiFlightController_CancelArrestFlying();
|
||||
USER_LOG_INFO(" - Disable arrest flying\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'K':
|
||||
case 'k':
|
||||
DjiFlightController_ExecuteEmergencyBrakeAction();
|
||||
USER_LOG_INFO(" - Brake\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'L':
|
||||
case 'l':
|
||||
DjiFlightController_CancelEmergencyBrakeAction();
|
||||
USER_LOG_INFO(" - Disable Brake\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'M':
|
||||
case 'm':
|
||||
DjiFlightController_ObtainJoystickCtrlAuthority();
|
||||
USER_LOG_INFO(" - Obtain joystick ctrl authority\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
}
|
||||
}
|
||||
@ -1086,5 +1098,22 @@ static T_DjiReturnCode DjiUser_FlightControlUpdateConfig(void)
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
#endif
|
||||
}
|
||||
static T_DjiReturnCode DjiUser_ShowCommandFlyingMenu(void)
|
||||
{
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
|
||||
osalHandler->TaskSleepMs(2);
|
||||
USER_LOG_INFO("Usage: [W] Front [A]-Left, [S]-Rear, [D]-Right");
|
||||
USER_LOG_INFO("Usage: [Q]-Up [E]-Down, [Z]-Yaw--, [C]-Yaw++");
|
||||
USER_LOG_INFO("Usage: [R]-Take off [F]-Force landing, [H]-Start go home, [Y]-Cancel go home");
|
||||
USER_LOG_INFO("Usage: [G]-Start landing [T]-Cancel landing, [V]-Confirm landing, [X]-Set home location");
|
||||
USER_LOG_INFO("Usage: [P]-Emergency stop motor, [B]-Turn on motors, [N]-Turn off motors, [J]-Update config");
|
||||
USER_LOG_INFO("Usage: [I]-Enable arrest flying, [O]-Disable arrest flying, [K]-Emergency brake, [L]-Diasble Brake");
|
||||
USER_LOG_INFO("Usage: [M]-Obtain joystick ctrl authority");
|
||||
osalHandler->TaskSleepMs(2);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
|
||||
@ -63,6 +63,8 @@ start:
|
||||
<< "| [8] Waypoint 3.0 sample - run airline mission by kmz file (not support on M300 RTK) |\n"
|
||||
<< "| [9] Interest point sample - run interest point mission by settings (only support on M3E/M3T) |\n"
|
||||
<< "| [a] EU-C6 FTS trigger sample - receive fts callback to trigger parachute function (only support on M3D/M3DT) |\n"
|
||||
<< "| [b] Slow rotate blade sample, only support on M400 |\n"
|
||||
<< "| [c] Select FTS pwm trigger position, only support on M4/M4T/M4D/M4TD |\n"
|
||||
<< std::endl;
|
||||
|
||||
std::cin >> inputSelectSample;
|
||||
@ -100,6 +102,12 @@ start:
|
||||
case 'a':
|
||||
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_FTS_TRIGGER);
|
||||
break;
|
||||
case 'b':
|
||||
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SLOW_ROTATE_BLADE);
|
||||
break;
|
||||
case 'c':
|
||||
DjiTest_FlightControlFtsPwmTriggerSample();
|
||||
break;
|
||||
case 'q':
|
||||
break;
|
||||
default:
|
||||
|
||||
@ -89,15 +89,7 @@ start:
|
||||
<<
|
||||
std::endl;
|
||||
std::cout
|
||||
<< "| [1] Select gimbal mount position at NO.1 payload port |"
|
||||
<<
|
||||
std::endl;
|
||||
std::cout
|
||||
<< "| [2] Select gimbal mount position at NO.2 payload port |"
|
||||
<<
|
||||
std::endl;
|
||||
std::cout
|
||||
<< "| [3] Select gimbal mount position at NO.3 payload port |"
|
||||
<< "| [1 ~ 4] Select gimbal mount position at NO.1~NO.4 |"
|
||||
<<
|
||||
std::endl;
|
||||
std::cout
|
||||
@ -110,7 +102,7 @@ start:
|
||||
return;
|
||||
}
|
||||
|
||||
if (mountPosition > '3' || mountPosition < '1') {
|
||||
if (mountPosition > '4' || mountPosition < '1') {
|
||||
USER_LOG_ERROR("Input mount position is invalid");
|
||||
goto start;
|
||||
}
|
||||
@ -247,6 +239,7 @@ start:
|
||||
T_DjiGimbalManagerRotation rotation;
|
||||
T_DjiAircraftInfoBaseInfo baseInfo;
|
||||
E_DjiAircraftSeries aircraftSeries;
|
||||
E_DjiFcSubscriptionTopic topicOfPayloadGimablAngle;
|
||||
|
||||
returnCode = DjiGimbalManager_Init();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -288,12 +281,24 @@ start:
|
||||
}
|
||||
else if (aircraftSeries == DJI_AIRCRAFT_SERIES_M30 || aircraftSeries == DJI_AIRCRAFT_SERIES_M3 ||
|
||||
aircraftSeries == DJI_AIRCRAFT_SERIES_M3D) {
|
||||
topicOfPayloadGimablAngle = DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES;
|
||||
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);
|
||||
goto end;
|
||||
}
|
||||
USER_LOG_INFO("Subscribe topic DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES succefully.");
|
||||
} else if (aircraftSeries == DJI_AIRCRAFT_SERIES_M400) {
|
||||
topicOfPayloadGimablAngle = gimbalMountPosition == 1 ? DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO1 :
|
||||
gimbalMountPosition == 2 ? DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO2 :
|
||||
gimbalMountPosition == 3 ? DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO3 :
|
||||
gimbalMountPosition == 4 ? DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO4 : DJI_FC_SUBSCRIPTION_TOPIC_TOTAL_NUMBER;
|
||||
returnCode = DjiFcSubscription_SubscribeTopic(topicOfPayloadGimablAngle, 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);
|
||||
goto end;
|
||||
}
|
||||
USER_LOG_INFO("Subscribe topic DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO%d succefully.", gimbalMountPosition);
|
||||
}
|
||||
|
||||
|
||||
@ -403,8 +408,8 @@ start:
|
||||
threeGimbalData.anglesData[gimbalMountPosition - 1].yaw);
|
||||
}
|
||||
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,
|
||||
aircraftSeries == DJI_AIRCRAFT_SERIES_M3D || aircraftSeries == DJI_AIRCRAFT_SERIES_M400) {
|
||||
returnCode = DjiFcSubscription_GetLatestValueOfTopic(topicOfPayloadGimablAngle,
|
||||
(uint8_t *) &gimbalAngles,
|
||||
sizeof(T_DjiFcSubscriptionGimbalAngles),
|
||||
×tamp);
|
||||
|
||||
@ -28,6 +28,7 @@
|
||||
#include <iostream>
|
||||
#include "dji_logger.h"
|
||||
#include "hms/test_hms.h"
|
||||
#include "dji_hms_customization.h"
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
|
||||
@ -77,6 +78,38 @@ start:
|
||||
}
|
||||
}
|
||||
|
||||
void DjiUser_RunHmsEnhanceSample(void)
|
||||
{
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
T_DjiHmsAlarmEnhancedSetting setting;
|
||||
|
||||
USER_LOG_INFO("shake motor times 3, interval 500ms...");
|
||||
setting.type = DJI_HMS_ALARM_ENHANCED_TYPE_SHAKE_MOTOR;
|
||||
setting.times = 3;
|
||||
setting.interval = 500;
|
||||
DjiHmsCustomization_AlarmEnhancedCtrl(DJI_HMS_ALARM_ENHANCED_ACTION_START, setting);
|
||||
osalHandler->TaskSleepMs(4000);
|
||||
|
||||
USER_LOG_INFO("play sound times 3, interval 500ms...");
|
||||
setting.type = DJI_HMS_ALARM_ENHANCED_PLAY_SOUND;
|
||||
DjiHmsCustomization_AlarmEnhancedCtrl(DJI_HMS_ALARM_ENHANCED_ACTION_START, setting);
|
||||
osalHandler->TaskSleepMs(4000);
|
||||
|
||||
USER_LOG_INFO("shake motor and play sound times 3, interval 500ms...");
|
||||
setting.times = 3;
|
||||
setting.type = DJI_HMS_ALARM_ENHANCED_PLAY_SOUND_AND_SHAKE_MOTOR;
|
||||
DjiHmsCustomization_AlarmEnhancedCtrl(DJI_HMS_ALARM_ENHANCED_ACTION_START, setting);
|
||||
osalHandler->TaskSleepMs(4000);
|
||||
|
||||
USER_LOG_INFO("shake motor and play sound times 20, interval 500ms, interrupt 3s exit...");
|
||||
setting.times = 20;
|
||||
setting.type = DJI_HMS_ALARM_ENHANCED_PLAY_SOUND_AND_SHAKE_MOTOR;
|
||||
DjiHmsCustomization_AlarmEnhancedCtrl(DJI_HMS_ALARM_ENHANCED_ACTION_START, setting);
|
||||
osalHandler->TaskSleepMs(4000);
|
||||
DjiHmsCustomization_AlarmEnhancedCtrl(DJI_HMS_ALARM_ENHANCED_ACTION_EXIT_ALL, setting);
|
||||
USER_LOG_INFO("AlarmEnhaned exit.");
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
|
||||
@ -40,6 +40,7 @@ extern "C" {
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
void DjiUser_RunHmsManagerSample(void);
|
||||
void DjiUser_RunHmsEnhanceSample(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
||||
@ -0,0 +1,6 @@
|
||||
classes= 80
|
||||
train = ~/COCO/train2017.txt
|
||||
valid = ~/COCO/val2017.txt
|
||||
names = coco.names
|
||||
backup = model
|
||||
|
||||
@ -0,0 +1,80 @@
|
||||
person
|
||||
bicycle
|
||||
car
|
||||
motorbike
|
||||
aeroplane
|
||||
bus
|
||||
train
|
||||
truck
|
||||
boat
|
||||
traffic light
|
||||
fire hydrant
|
||||
stop sign
|
||||
parking meter
|
||||
bench
|
||||
bird
|
||||
cat
|
||||
dog
|
||||
horse
|
||||
sheep
|
||||
cow
|
||||
elephant
|
||||
bear
|
||||
zebra
|
||||
giraffe
|
||||
backpack
|
||||
umbrella
|
||||
handbag
|
||||
tie
|
||||
suitcase
|
||||
frisbee
|
||||
skis
|
||||
snowboard
|
||||
sports ball
|
||||
kite
|
||||
baseball bat
|
||||
baseball glove
|
||||
skateboard
|
||||
surfboard
|
||||
tennis racket
|
||||
bottle
|
||||
wine glass
|
||||
cup
|
||||
fork
|
||||
knife
|
||||
spoon
|
||||
bowl
|
||||
banana
|
||||
apple
|
||||
sandwich
|
||||
orange
|
||||
broccoli
|
||||
carrot
|
||||
hot dog
|
||||
pizza
|
||||
donut
|
||||
cake
|
||||
chair
|
||||
sofa
|
||||
pottedplant
|
||||
bed
|
||||
diningtable
|
||||
toilet
|
||||
tvmonitor
|
||||
laptop
|
||||
mouse
|
||||
remote
|
||||
keyboard
|
||||
cell phone
|
||||
microwave
|
||||
oven
|
||||
toaster
|
||||
sink
|
||||
refrigerator
|
||||
book
|
||||
clock
|
||||
vase
|
||||
scissors
|
||||
teddy bear
|
||||
hair drier
|
||||
toothbrush
|
||||
@ -0,0 +1,244 @@
|
||||
CUDA-version: 10010 (10010), cuDNN: 7.6.5, GPU count: 4
|
||||
OpenCV version: 4.9.1
|
||||
0,1,2,3
|
||||
0 : compute_capability = 610, cudnn_half = 0, GPU: GeForce GTX 1080 Ti
|
||||
net.optimized_memory = 0
|
||||
mini_batch = 1, batch = 1, time_steps = 1, train = 0
|
||||
layer filters size/strd(dil) input output
|
||||
0 Create CUDA-stream - 0
|
||||
Create cudnn-handle 0
|
||||
conv 8 3 x 3/ 2 320 x 320 x 3 -> 160 x 160 x 8 0.011 BF
|
||||
1 conv 8 1 x 1/ 1 160 x 160 x 8 -> 160 x 160 x 8 0.003 BF
|
||||
2 conv 8/ 8 3 x 3/ 1 160 x 160 x 8 -> 160 x 160 x 8 0.004 BF
|
||||
3 conv 4 1 x 1/ 1 160 x 160 x 8 -> 160 x 160 x 4 0.002 BF
|
||||
4 conv 8 1 x 1/ 1 160 x 160 x 4 -> 160 x 160 x 8 0.002 BF
|
||||
5 conv 8/ 8 3 x 3/ 1 160 x 160 x 8 -> 160 x 160 x 8 0.004 BF
|
||||
6 conv 4 1 x 1/ 1 160 x 160 x 8 -> 160 x 160 x 4 0.002 BF
|
||||
7 dropout p = 0.150 102400 -> 102400
|
||||
8 Shortcut Layer: 3, wt = 0, wn = 0, outputs: 160 x 160 x 4 0.000 BF
|
||||
9 conv 24 1 x 1/ 1 160 x 160 x 4 -> 160 x 160 x 24 0.005 BF
|
||||
10 conv 24/ 24 3 x 3/ 2 160 x 160 x 24 -> 80 x 80 x 24 0.003 BF
|
||||
11 conv 8 1 x 1/ 1 80 x 80 x 24 -> 80 x 80 x 8 0.002 BF
|
||||
12 conv 32 1 x 1/ 1 80 x 80 x 8 -> 80 x 80 x 32 0.003 BF
|
||||
13 conv 32/ 32 3 x 3/ 1 80 x 80 x 32 -> 80 x 80 x 32 0.004 BF
|
||||
14 conv 8 1 x 1/ 1 80 x 80 x 32 -> 80 x 80 x 8 0.003 BF
|
||||
15 dropout p = 0.150 51200 -> 51200
|
||||
16 Shortcut Layer: 11, wt = 0, wn = 0, outputs: 80 x 80 x 8 0.000 BF
|
||||
17 conv 32 1 x 1/ 1 80 x 80 x 8 -> 80 x 80 x 32 0.003 BF
|
||||
18 conv 32/ 32 3 x 3/ 1 80 x 80 x 32 -> 80 x 80 x 32 0.004 BF
|
||||
19 conv 8 1 x 1/ 1 80 x 80 x 32 -> 80 x 80 x 8 0.003 BF
|
||||
20 dropout p = 0.150 51200 -> 51200
|
||||
21 Shortcut Layer: 16, wt = 0, wn = 0, outputs: 80 x 80 x 8 0.000 BF
|
||||
22 conv 32 1 x 1/ 1 80 x 80 x 8 -> 80 x 80 x 32 0.003 BF
|
||||
23 conv 32/ 32 3 x 3/ 2 80 x 80 x 32 -> 40 x 40 x 32 0.001 BF
|
||||
24 conv 8 1 x 1/ 1 40 x 40 x 32 -> 40 x 40 x 8 0.001 BF
|
||||
25 conv 48 1 x 1/ 1 40 x 40 x 8 -> 40 x 40 x 48 0.001 BF
|
||||
26 conv 48/ 48 3 x 3/ 1 40 x 40 x 48 -> 40 x 40 x 48 0.001 BF
|
||||
27 conv 8 1 x 1/ 1 40 x 40 x 48 -> 40 x 40 x 8 0.001 BF
|
||||
28 dropout p = 0.150 12800 -> 12800
|
||||
29 Shortcut Layer: 24, wt = 0, wn = 0, outputs: 40 x 40 x 8 0.000 BF
|
||||
30 conv 48 1 x 1/ 1 40 x 40 x 8 -> 40 x 40 x 48 0.001 BF
|
||||
31 conv 48/ 48 3 x 3/ 1 40 x 40 x 48 -> 40 x 40 x 48 0.001 BF
|
||||
32 conv 8 1 x 1/ 1 40 x 40 x 48 -> 40 x 40 x 8 0.001 BF
|
||||
33 dropout p = 0.150 12800 -> 12800
|
||||
34 Shortcut Layer: 29, wt = 0, wn = 0, outputs: 40 x 40 x 8 0.000 BF
|
||||
35 conv 48 1 x 1/ 1 40 x 40 x 8 -> 40 x 40 x 48 0.001 BF
|
||||
36 conv 48/ 48 3 x 3/ 1 40 x 40 x 48 -> 40 x 40 x 48 0.001 BF
|
||||
37 conv 16 1 x 1/ 1 40 x 40 x 48 -> 40 x 40 x 16 0.002 BF
|
||||
38 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF
|
||||
39 conv 96/ 96 3 x 3/ 1 40 x 40 x 96 -> 40 x 40 x 96 0.003 BF
|
||||
40 conv 16 1 x 1/ 1 40 x 40 x 96 -> 40 x 40 x 16 0.005 BF
|
||||
41 dropout p = 0.150 25600 -> 25600
|
||||
42 Shortcut Layer: 37, wt = 0, wn = 0, outputs: 40 x 40 x 16 0.000 BF
|
||||
43 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF
|
||||
44 conv 96/ 96 3 x 3/ 1 40 x 40 x 96 -> 40 x 40 x 96 0.003 BF
|
||||
45 conv 16 1 x 1/ 1 40 x 40 x 96 -> 40 x 40 x 16 0.005 BF
|
||||
46 dropout p = 0.150 25600 -> 25600
|
||||
47 Shortcut Layer: 42, wt = 0, wn = 0, outputs: 40 x 40 x 16 0.000 BF
|
||||
48 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF
|
||||
49 conv 96/ 96 3 x 3/ 1 40 x 40 x 96 -> 40 x 40 x 96 0.003 BF
|
||||
50 conv 16 1 x 1/ 1 40 x 40 x 96 -> 40 x 40 x 16 0.005 BF
|
||||
51 dropout p = 0.150 25600 -> 25600
|
||||
52 Shortcut Layer: 47, wt = 0, wn = 0, outputs: 40 x 40 x 16 0.000 BF
|
||||
53 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF
|
||||
54 conv 96/ 96 3 x 3/ 1 40 x 40 x 96 -> 40 x 40 x 96 0.003 BF
|
||||
55 conv 16 1 x 1/ 1 40 x 40 x 96 -> 40 x 40 x 16 0.005 BF
|
||||
56 dropout p = 0.150 25600 -> 25600
|
||||
57 Shortcut Layer: 52, wt = 0, wn = 0, outputs: 40 x 40 x 16 0.000 BF
|
||||
58 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF
|
||||
59 conv 96/ 96 3 x 3/ 2 40 x 40 x 96 -> 20 x 20 x 96 0.001 BF
|
||||
60 conv 24 1 x 1/ 1 20 x 20 x 96 -> 20 x 20 x 24 0.002 BF
|
||||
61 conv 136 1 x 1/ 1 20 x 20 x 24 -> 20 x 20 x 136 0.003 BF
|
||||
62 conv 136/ 136 3 x 3/ 1 20 x 20 x 136 -> 20 x 20 x 136 0.001 BF
|
||||
63 conv 24 1 x 1/ 1 20 x 20 x 136 -> 20 x 20 x 24 0.003 BF
|
||||
64 dropout p = 0.150 9600 -> 9600
|
||||
65 Shortcut Layer: 60, wt = 0, wn = 0, outputs: 20 x 20 x 24 0.000 BF
|
||||
66 conv 136 1 x 1/ 1 20 x 20 x 24 -> 20 x 20 x 136 0.003 BF
|
||||
67 conv 136/ 136 3 x 3/ 1 20 x 20 x 136 -> 20 x 20 x 136 0.001 BF
|
||||
68 conv 24 1 x 1/ 1 20 x 20 x 136 -> 20 x 20 x 24 0.003 BF
|
||||
69 dropout p = 0.150 9600 -> 9600
|
||||
70 Shortcut Layer: 65, wt = 0, wn = 0, outputs: 20 x 20 x 24 0.000 BF
|
||||
71 conv 136 1 x 1/ 1 20 x 20 x 24 -> 20 x 20 x 136 0.003 BF
|
||||
72 conv 136/ 136 3 x 3/ 1 20 x 20 x 136 -> 20 x 20 x 136 0.001 BF
|
||||
73 conv 24 1 x 1/ 1 20 x 20 x 136 -> 20 x 20 x 24 0.003 BF
|
||||
74 dropout p = 0.150 9600 -> 9600
|
||||
75 Shortcut Layer: 70, wt = 0, wn = 0, outputs: 20 x 20 x 24 0.000 BF
|
||||
76 conv 136 1 x 1/ 1 20 x 20 x 24 -> 20 x 20 x 136 0.003 BF
|
||||
77 conv 136/ 136 3 x 3/ 1 20 x 20 x 136 -> 20 x 20 x 136 0.001 BF
|
||||
78 conv 24 1 x 1/ 1 20 x 20 x 136 -> 20 x 20 x 24 0.003 BF
|
||||
79 dropout p = 0.150 9600 -> 9600
|
||||
80 Shortcut Layer: 75, wt = 0, wn = 0, outputs: 20 x 20 x 24 0.000 BF
|
||||
81 conv 136 1 x 1/ 1 20 x 20 x 24 -> 20 x 20 x 136 0.003 BF
|
||||
82 conv 136/ 136 3 x 3/ 2 20 x 20 x 136 -> 10 x 10 x 136 0.000 BF
|
||||
83 conv 48 1 x 1/ 1 10 x 10 x 136 -> 10 x 10 x 48 0.001 BF
|
||||
84 conv 224 1 x 1/ 1 10 x 10 x 48 -> 10 x 10 x 224 0.002 BF
|
||||
85 conv 224/ 224 3 x 3/ 1 10 x 10 x 224 -> 10 x 10 x 224 0.000 BF
|
||||
86 conv 48 1 x 1/ 1 10 x 10 x 224 -> 10 x 10 x 48 0.002 BF
|
||||
87 dropout p = 0.150 4800 -> 4800
|
||||
88 Shortcut Layer: 83, wt = 0, wn = 0, outputs: 10 x 10 x 48 0.000 BF
|
||||
89 conv 224 1 x 1/ 1 10 x 10 x 48 -> 10 x 10 x 224 0.002 BF
|
||||
90 conv 224/ 224 3 x 3/ 1 10 x 10 x 224 -> 10 x 10 x 224 0.000 BF
|
||||
91 conv 48 1 x 1/ 1 10 x 10 x 224 -> 10 x 10 x 48 0.002 BF
|
||||
92 dropout p = 0.150 4800 -> 4800
|
||||
93 Shortcut Layer: 88, wt = 0, wn = 0, outputs: 10 x 10 x 48 0.000 BF
|
||||
94 conv 224 1 x 1/ 1 10 x 10 x 48 -> 10 x 10 x 224 0.002 BF
|
||||
95 conv 224/ 224 3 x 3/ 1 10 x 10 x 224 -> 10 x 10 x 224 0.000 BF
|
||||
96 conv 48 1 x 1/ 1 10 x 10 x 224 -> 10 x 10 x 48 0.002 BF
|
||||
97 dropout p = 0.150 4800 -> 4800
|
||||
98 Shortcut Layer: 93, wt = 0, wn = 0, outputs: 10 x 10 x 48 0.000 BF
|
||||
99 conv 224 1 x 1/ 1 10 x 10 x 48 -> 10 x 10 x 224 0.002 BF
|
||||
100 conv 224/ 224 3 x 3/ 1 10 x 10 x 224 -> 10 x 10 x 224 0.000 BF
|
||||
101 conv 48 1 x 1/ 1 10 x 10 x 224 -> 10 x 10 x 48 0.002 BF
|
||||
102 dropout p = 0.150 4800 -> 4800
|
||||
103 Shortcut Layer: 98, wt = 0, wn = 0, outputs: 10 x 10 x 48 0.000 BF
|
||||
104 conv 224 1 x 1/ 1 10 x 10 x 48 -> 10 x 10 x 224 0.002 BF
|
||||
105 conv 224/ 224 3 x 3/ 1 10 x 10 x 224 -> 10 x 10 x 224 0.000 BF
|
||||
106 conv 48 1 x 1/ 1 10 x 10 x 224 -> 10 x 10 x 48 0.002 BF
|
||||
107 dropout p = 0.150 4800 -> 4800
|
||||
108 Shortcut Layer: 103, wt = 0, wn = 0, outputs: 10 x 10 x 48 0.000 BF
|
||||
109 max 3x 3/ 1 10 x 10 x 48 -> 10 x 10 x 48 0.000 BF
|
||||
110 route 108 -> 10 x 10 x 48
|
||||
111 max 5x 5/ 1 10 x 10 x 48 -> 10 x 10 x 48 0.000 BF
|
||||
112 route 108 -> 10 x 10 x 48
|
||||
113 max 9x 9/ 1 10 x 10 x 48 -> 10 x 10 x 48 0.000 BF
|
||||
114 route 113 111 109 108 -> 10 x 10 x 192
|
||||
115 conv 96 1 x 1/ 1 10 x 10 x 192 -> 10 x 10 x 96 0.004 BF
|
||||
116 conv 96/ 96 5 x 5/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.000 BF
|
||||
117 conv 96 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.002 BF
|
||||
118 conv 96/ 96 5 x 5/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.000 BF
|
||||
119 conv 96 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.002 BF
|
||||
120 conv 255 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 255 0.005 BF
|
||||
121 yolo
|
||||
[yolo] params: iou loss: ciou (4), iou_norm: 0.07, obj_norm: 1.00, cls_norm: 1.00, delta_norm: 1.00, scale_x_y: 1.00
|
||||
nms_kind: greedynms (1), beta = 0.600000
|
||||
122 route 115 -> 10 x 10 x 96
|
||||
123 upsample 2x 10 x 10 x 96 -> 20 x 20 x 96
|
||||
124 route 123 80 -> 20 x 20 x 120
|
||||
125 conv 120/ 120 5 x 5/ 1 20 x 20 x 120 -> 20 x 20 x 120 0.002 BF
|
||||
126 conv 120 1 x 1/ 1 20 x 20 x 120 -> 20 x 20 x 120 0.012 BF
|
||||
127 conv 120/ 120 5 x 5/ 1 20 x 20 x 120 -> 20 x 20 x 120 0.002 BF
|
||||
128 conv 120 1 x 1/ 1 20 x 20 x 120 -> 20 x 20 x 120 0.012 BF
|
||||
129 conv 255 1 x 1/ 1 20 x 20 x 120 -> 20 x 20 x 255 0.024 BF
|
||||
130 yolo
|
||||
[yolo] params: iou loss: ciou (4), iou_norm: 0.07, obj_norm: 1.00, cls_norm: 1.00, delta_norm: 1.00, scale_x_y: 1.00
|
||||
nms_kind: greedynms (1), beta = 0.600000
|
||||
Total BFLOPS 0.252
|
||||
avg_outputs = 62893
|
||||
Allocate additional workspace_size = 1.23 MB
|
||||
Loading weights from yolo-fastest-1.1.weights...
|
||||
seen 64, trained: 14231 K-images (222 Kilo-batches_64)
|
||||
Done! Loaded 131 layers from weights-file
|
||||
|
||||
calculation mAP (mean average precision)...
|
||||
Detection layer: 121 - type = 28
|
||||
Detection layer: 130 - type = 28
|
||||
4952
|
||||
detections_count = 897029, unique_truth_count = 36335
|
||||
class_id = 0, name = person, ap = 45.27% (TP = 4021, FP = 6119)
|
||||
class_id = 1, name = bicycle, ap = 16.88% (TP = 43, FP = 72)
|
||||
class_id = 2, name = car, ap = 20.98% (TP = 484, FP = 1112)
|
||||
class_id = 3, name = motorcycle, ap = 36.12% (TP = 129, FP = 160)
|
||||
class_id = 4, name = airplane, ap = 57.68% (TP = 81, FP = 57)
|
||||
class_id = 5, name = bus, ap = 52.42% (TP = 125, FP = 80)
|
||||
class_id = 6, name = train, ap = 63.20% (TP = 110, FP = 60)
|
||||
class_id = 7, name = truck, ap = 18.15% (TP = 70, FP = 104)
|
||||
class_id = 8, name = boat, ap = 12.82% (TP = 70, FP = 188)
|
||||
class_id = 9, name = traffic light, ap = 9.76% (TP = 76, FP = 162)
|
||||
class_id = 10, name = fire hydrant, ap = 49.26% (TP = 46, FP = 40)
|
||||
class_id = 11, name = stop sign, ap = 51.04% (TP = 39, FP = 21)
|
||||
class_id = 12, name = parking meter, ap = 25.85% (TP = 13, FP = 5)
|
||||
class_id = 13, name = bench, ap = 12.02% (TP = 43, FP = 55)
|
||||
class_id = 14, name = bird, ap = 14.24% (TP = 64, FP = 137)
|
||||
class_id = 15, name = cat, ap = 59.32% (TP = 98, FP = 126)
|
||||
class_id = 16, name = dog, ap = 41.95% (TP = 80, FP = 95)
|
||||
class_id = 17, name = horse, ap = 43.46% (TP = 120, FP = 151)
|
||||
class_id = 18, name = sheep, ap = 33.25% (TP = 147, FP = 285)
|
||||
class_id = 19, name = cow, ap = 35.18% (TP = 146, FP = 205)
|
||||
class_id = 20, name = elephant, ap = 59.49% (TP = 151, FP = 152)
|
||||
class_id = 21, name = bear, ap = 58.50% (TP = 46, FP = 44)
|
||||
class_id = 22, name = zebra, ap = 66.36% (TP = 172, FP = 123)
|
||||
class_id = 23, name = giraffe, ap = 65.48% (TP = 150, FP = 63)
|
||||
class_id = 24, name = backpack, ap = 1.91% (TP = 4, FP = 22)
|
||||
class_id = 25, name = umbrella, ap = 21.44% (TP = 91, FP = 138)
|
||||
class_id = 26, name = handbag, ap = 0.61% (TP = 1, FP = 23)
|
||||
class_id = 27, name = tie, ap = 10.44% (TP = 31, FP = 94)
|
||||
class_id = 28, name = suitcase, ap = 12.93% (TP = 39, FP = 78)
|
||||
class_id = 29, name = frisbee, ap = 27.25% (TP = 28, FP = 41)
|
||||
class_id = 30, name = skis, ap = 11.67% (TP = 37, FP = 132)
|
||||
class_id = 31, name = snowboard, ap = 10.36% (TP = 6, FP = 10)
|
||||
class_id = 32, name = sports ball, ap = 17.34% (TP = 48, FP = 62)
|
||||
class_id = 33, name = kite, ap = 25.58% (TP = 117, FP = 232)
|
||||
class_id = 34, name = baseball bat, ap = 11.47% (TP = 15, FP = 27)
|
||||
class_id = 35, name = baseball glove, ap = 10.58% (TP = 20, FP = 61)
|
||||
class_id = 36, name = skateboard, ap = 18.58% (TP = 44, FP = 85)
|
||||
class_id = 37, name = surfboard, ap = 14.43% (TP = 50, FP = 172)
|
||||
class_id = 38, name = tennis racket, ap = 22.89% (TP = 67, FP = 116)
|
||||
class_id = 39, name = bottle, ap = 7.63% (TP = 69, FP = 146)
|
||||
class_id = 40, name = wine glass, ap = 7.97% (TP = 18, FP = 67)
|
||||
class_id = 41, name = cup, ap = 13.11% (TP = 116, FP = 243)
|
||||
class_id = 42, name = fork, ap = 4.41% (TP = 9, FP = 13)
|
||||
class_id = 43, name = knife, ap = 1.48% (TP = 2, FP = 14)
|
||||
class_id = 44, name = spoon, ap = 0.77% (TP = 1, FP = 6)
|
||||
class_id = 45, name = bowl, ap = 23.25% (TP = 134, FP = 241)
|
||||
class_id = 46, name = banana, ap = 8.99% (TP = 39, FP = 105)
|
||||
class_id = 47, name = apple, ap = 5.32% (TP = 13, FP = 37)
|
||||
class_id = 48, name = sandwich, ap = 23.40% (TP = 35, FP = 67)
|
||||
class_id = 49, name = orange, ap = 16.69% (TP = 52, FP = 91)
|
||||
class_id = 50, name = broccoli, ap = 16.88% (TP = 65, FP = 164)
|
||||
class_id = 51, name = carrot, ap = 7.64% (TP = 27, FP = 80)
|
||||
class_id = 52, name = hot dog, ap = 14.46% (TP = 11, FP = 31)
|
||||
class_id = 53, name = pizza, ap = 41.55% (TP = 113, FP = 124)
|
||||
class_id = 54, name = donut, ap = 19.84% (TP = 65, FP = 152)
|
||||
class_id = 55, name = cake, ap = 18.44% (TP = 45, FP = 72)
|
||||
class_id = 56, name = chair, ap = 10.04% (TP = 142, FP = 275)
|
||||
class_id = 57, name = couch, ap = 29.89% (TP = 53, FP = 101)
|
||||
class_id = 58, name = potted plant, ap = 10.76% (TP = 29, FP = 84)
|
||||
class_id = 59, name = bed, ap = 43.32% (TP = 57, FP = 71)
|
||||
class_id = 60, name = dining table, ap = 22.00% (TP = 183, FP = 283)
|
||||
class_id = 61, name = toilet, ap = 58.93% (TP = 94, FP = 89)
|
||||
class_id = 62, name = tv, ap = 47.13% (TP = 123, FP = 107)
|
||||
class_id = 63, name = laptop, ap = 40.93% (TP = 75, FP = 112)
|
||||
class_id = 64, name = mouse, ap = 32.37% (TP = 29, FP = 26)
|
||||
class_id = 65, name = remote, ap = 4.22% (TP = 12, FP = 19)
|
||||
class_id = 66, name = keyboard, ap = 31.90% (TP = 51, FP = 67)
|
||||
class_id = 67, name = cell phone, ap = 15.28% (TP = 30, FP = 30)
|
||||
class_id = 68, name = microwave, ap = 39.49% (TP = 20, FP = 14)
|
||||
class_id = 69, name = oven, ap = 24.75% (TP = 34, FP = 45)
|
||||
class_id = 70, name = toaster, ap = 2.32% (TP = 0, FP = 0)
|
||||
class_id = 71, name = sink, ap = 20.24% (TP = 46, FP = 86)
|
||||
class_id = 72, name = refrigerator, ap = 30.95% (TP = 42, FP = 44)
|
||||
class_id = 73, name = book, ap = 1.74% (TP = 45, FP = 334)
|
||||
class_id = 74, name = clock, ap = 32.38% (TP = 103, FP = 127)
|
||||
class_id = 75, name = vase, ap = 13.89% (TP = 40, FP = 48)
|
||||
class_id = 76, name = scissors, ap = 6.25% (TP = 1, FP = 3)
|
||||
class_id = 77, name = teddy bear, ap = 33.81% (TP = 59, FP = 56)
|
||||
class_id = 78, name = hair drier, ap = 0.00% (TP = 0, FP = 0)
|
||||
class_id = 79, name = toothbrush, ap = 1.16% (TP = 0, FP = 2)
|
||||
|
||||
for conf_thresh = 0.25, precision = 0.39, recall = 0.25, F1-score = 0.31
|
||||
for conf_thresh = 0.25, TP = 9204, FP = 14585, FN = 27131, average IoU = 27.42 %
|
||||
|
||||
IoU threshold = 50 %, used Area-Under-Curve for each unique Recall
|
||||
mean average precision (mAP@0.50) = 0.243967, or 24.40 %
|
||||
Total Detection Time: 133 Seconds
|
||||
|
||||
@ -0,0 +1,239 @@
|
||||
mini_batch = 1, batch = 1, time_steps = 1, train = 0
|
||||
layer filters size/strd(dil) input output
|
||||
0 Create CUDA-stream - 0
|
||||
Create cudnn-handle 0
|
||||
conv 16 3 x 3/ 2 320 x 320 x 3 -> 160 x 160 x 16 0.022 BF
|
||||
1 conv 16 1 x 1/ 1 160 x 160 x 16 -> 160 x 160 x 16 0.013 BF
|
||||
2 conv 16/ 16 3 x 3/ 1 160 x 160 x 16 -> 160 x 160 x 16 0.007 BF
|
||||
3 conv 8 1 x 1/ 1 160 x 160 x 16 -> 160 x 160 x 8 0.007 BF
|
||||
4 conv 16 1 x 1/ 1 160 x 160 x 8 -> 160 x 160 x 16 0.007 BF
|
||||
5 conv 16/ 16 3 x 3/ 1 160 x 160 x 16 -> 160 x 160 x 16 0.007 BF
|
||||
6 conv 8 1 x 1/ 1 160 x 160 x 16 -> 160 x 160 x 8 0.007 BF
|
||||
7 dropout p = 0.200 204800 -> 204800
|
||||
8 Shortcut Layer: 3, wt = 0, wn = 0, outputs: 160 x 160 x 8 0.000 BF
|
||||
9 conv 48 1 x 1/ 1 160 x 160 x 8 -> 160 x 160 x 48 0.020 BF
|
||||
10 conv 48/ 48 3 x 3/ 2 160 x 160 x 48 -> 80 x 80 x 48 0.006 BF
|
||||
11 conv 16 1 x 1/ 1 80 x 80 x 48 -> 80 x 80 x 16 0.010 BF
|
||||
12 conv 64 1 x 1/ 1 80 x 80 x 16 -> 80 x 80 x 64 0.013 BF
|
||||
13 conv 64/ 64 3 x 3/ 1 80 x 80 x 64 -> 80 x 80 x 64 0.007 BF
|
||||
14 conv 16 1 x 1/ 1 80 x 80 x 64 -> 80 x 80 x 16 0.013 BF
|
||||
15 dropout p = 0.200 102400 -> 102400
|
||||
16 Shortcut Layer: 11, wt = 0, wn = 0, outputs: 80 x 80 x 16 0.000 BF
|
||||
17 conv 64 1 x 1/ 1 80 x 80 x 16 -> 80 x 80 x 64 0.013 BF
|
||||
18 conv 64/ 64 3 x 3/ 1 80 x 80 x 64 -> 80 x 80 x 64 0.007 BF
|
||||
19 conv 16 1 x 1/ 1 80 x 80 x 64 -> 80 x 80 x 16 0.013 BF
|
||||
20 dropout p = 0.200 102400 -> 102400
|
||||
21 Shortcut Layer: 16, wt = 0, wn = 0, outputs: 80 x 80 x 16 0.000 BF
|
||||
22 conv 64 1 x 1/ 1 80 x 80 x 16 -> 80 x 80 x 64 0.013 BF
|
||||
23 conv 64/ 64 3 x 3/ 2 80 x 80 x 64 -> 40 x 40 x 64 0.002 BF
|
||||
24 conv 16 1 x 1/ 1 40 x 40 x 64 -> 40 x 40 x 16 0.003 BF
|
||||
25 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF
|
||||
26 conv 96/ 96 3 x 3/ 1 40 x 40 x 96 -> 40 x 40 x 96 0.003 BF
|
||||
27 conv 16 1 x 1/ 1 40 x 40 x 96 -> 40 x 40 x 16 0.005 BF
|
||||
28 dropout p = 0.200 25600 -> 25600
|
||||
29 Shortcut Layer: 24, wt = 0, wn = 0, outputs: 40 x 40 x 16 0.000 BF
|
||||
30 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF
|
||||
31 conv 96/ 96 3 x 3/ 1 40 x 40 x 96 -> 40 x 40 x 96 0.003 BF
|
||||
32 conv 16 1 x 1/ 1 40 x 40 x 96 -> 40 x 40 x 16 0.005 BF
|
||||
33 dropout p = 0.200 25600 -> 25600
|
||||
34 Shortcut Layer: 29, wt = 0, wn = 0, outputs: 40 x 40 x 16 0.000 BF
|
||||
35 conv 96 1 x 1/ 1 40 x 40 x 16 -> 40 x 40 x 96 0.005 BF
|
||||
36 conv 96/ 96 3 x 3/ 1 40 x 40 x 96 -> 40 x 40 x 96 0.003 BF
|
||||
37 conv 32 1 x 1/ 1 40 x 40 x 96 -> 40 x 40 x 32 0.010 BF
|
||||
38 conv 192 1 x 1/ 1 40 x 40 x 32 -> 40 x 40 x 192 0.020 BF
|
||||
39 conv 192/ 192 3 x 3/ 1 40 x 40 x 192 -> 40 x 40 x 192 0.006 BF
|
||||
40 conv 32 1 x 1/ 1 40 x 40 x 192 -> 40 x 40 x 32 0.020 BF
|
||||
41 dropout p = 0.200 51200 -> 51200
|
||||
42 Shortcut Layer: 37, wt = 0, wn = 0, outputs: 40 x 40 x 32 0.000 BF
|
||||
43 conv 192 1 x 1/ 1 40 x 40 x 32 -> 40 x 40 x 192 0.020 BF
|
||||
44 conv 192/ 192 3 x 3/ 1 40 x 40 x 192 -> 40 x 40 x 192 0.006 BF
|
||||
45 conv 32 1 x 1/ 1 40 x 40 x 192 -> 40 x 40 x 32 0.020 BF
|
||||
46 dropout p = 0.200 51200 -> 51200
|
||||
47 Shortcut Layer: 42, wt = 0, wn = 0, outputs: 40 x 40 x 32 0.000 BF
|
||||
48 conv 192 1 x 1/ 1 40 x 40 x 32 -> 40 x 40 x 192 0.020 BF
|
||||
49 conv 192/ 192 3 x 3/ 1 40 x 40 x 192 -> 40 x 40 x 192 0.006 BF
|
||||
50 conv 32 1 x 1/ 1 40 x 40 x 192 -> 40 x 40 x 32 0.020 BF
|
||||
51 dropout p = 0.200 51200 -> 51200
|
||||
52 Shortcut Layer: 47, wt = 0, wn = 0, outputs: 40 x 40 x 32 0.000 BF
|
||||
53 conv 192 1 x 1/ 1 40 x 40 x 32 -> 40 x 40 x 192 0.020 BF
|
||||
54 conv 192/ 192 3 x 3/ 1 40 x 40 x 192 -> 40 x 40 x 192 0.006 BF
|
||||
55 conv 32 1 x 1/ 1 40 x 40 x 192 -> 40 x 40 x 32 0.020 BF
|
||||
56 dropout p = 0.200 51200 -> 51200
|
||||
57 Shortcut Layer: 52, wt = 0, wn = 0, outputs: 40 x 40 x 32 0.000 BF
|
||||
58 conv 192 1 x 1/ 1 40 x 40 x 32 -> 40 x 40 x 192 0.020 BF
|
||||
59 conv 192/ 192 3 x 3/ 2 40 x 40 x 192 -> 20 x 20 x 192 0.001 BF
|
||||
60 conv 48 1 x 1/ 1 20 x 20 x 192 -> 20 x 20 x 48 0.007 BF
|
||||
61 conv 272 1 x 1/ 1 20 x 20 x 48 -> 20 x 20 x 272 0.010 BF
|
||||
62 conv 272/ 272 3 x 3/ 1 20 x 20 x 272 -> 20 x 20 x 272 0.002 BF
|
||||
63 conv 48 1 x 1/ 1 20 x 20 x 272 -> 20 x 20 x 48 0.010 BF
|
||||
64 dropout p = 0.200 19200 -> 19200
|
||||
65 Shortcut Layer: 60, wt = 0, wn = 0, outputs: 20 x 20 x 48 0.000 BF
|
||||
66 conv 272 1 x 1/ 1 20 x 20 x 48 -> 20 x 20 x 272 0.010 BF
|
||||
67 conv 272/ 272 3 x 3/ 1 20 x 20 x 272 -> 20 x 20 x 272 0.002 BF
|
||||
68 conv 48 1 x 1/ 1 20 x 20 x 272 -> 20 x 20 x 48 0.010 BF
|
||||
69 dropout p = 0.200 19200 -> 19200
|
||||
70 Shortcut Layer: 65, wt = 0, wn = 0, outputs: 20 x 20 x 48 0.000 BF
|
||||
71 conv 272 1 x 1/ 1 20 x 20 x 48 -> 20 x 20 x 272 0.010 BF
|
||||
72 conv 272/ 272 3 x 3/ 1 20 x 20 x 272 -> 20 x 20 x 272 0.002 BF
|
||||
73 conv 48 1 x 1/ 1 20 x 20 x 272 -> 20 x 20 x 48 0.010 BF
|
||||
74 dropout p = 0.200 19200 -> 19200
|
||||
75 Shortcut Layer: 70, wt = 0, wn = 0, outputs: 20 x 20 x 48 0.000 BF
|
||||
76 conv 272 1 x 1/ 1 20 x 20 x 48 -> 20 x 20 x 272 0.010 BF
|
||||
77 conv 272/ 272 3 x 3/ 1 20 x 20 x 272 -> 20 x 20 x 272 0.002 BF
|
||||
78 conv 48 1 x 1/ 1 20 x 20 x 272 -> 20 x 20 x 48 0.010 BF
|
||||
79 dropout p = 0.200 19200 -> 19200
|
||||
80 Shortcut Layer: 75, wt = 0, wn = 0, outputs: 20 x 20 x 48 0.000 BF
|
||||
81 conv 272 1 x 1/ 1 20 x 20 x 48 -> 20 x 20 x 272 0.010 BF
|
||||
82 conv 272/ 272 3 x 3/ 2 20 x 20 x 272 -> 10 x 10 x 272 0.000 BF
|
||||
83 conv 96 1 x 1/ 1 10 x 10 x 272 -> 10 x 10 x 96 0.005 BF
|
||||
84 conv 448 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 448 0.009 BF
|
||||
85 conv 448/ 448 3 x 3/ 1 10 x 10 x 448 -> 10 x 10 x 448 0.001 BF
|
||||
86 conv 96 1 x 1/ 1 10 x 10 x 448 -> 10 x 10 x 96 0.009 BF
|
||||
87 dropout p = 0.200 9600 -> 9600
|
||||
88 Shortcut Layer: 83, wt = 0, wn = 0, outputs: 10 x 10 x 96 0.000 BF
|
||||
89 conv 448 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 448 0.009 BF
|
||||
90 conv 448/ 448 3 x 3/ 1 10 x 10 x 448 -> 10 x 10 x 448 0.001 BF
|
||||
91 conv 96 1 x 1/ 1 10 x 10 x 448 -> 10 x 10 x 96 0.009 BF
|
||||
92 dropout p = 0.200 9600 -> 9600
|
||||
93 Shortcut Layer: 88, wt = 0, wn = 0, outputs: 10 x 10 x 96 0.000 BF
|
||||
94 conv 448 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 448 0.009 BF
|
||||
95 conv 448/ 448 3 x 3/ 1 10 x 10 x 448 -> 10 x 10 x 448 0.001 BF
|
||||
96 conv 96 1 x 1/ 1 10 x 10 x 448 -> 10 x 10 x 96 0.009 BF
|
||||
97 dropout p = 0.200 9600 -> 9600
|
||||
98 Shortcut Layer: 93, wt = 0, wn = 0, outputs: 10 x 10 x 96 0.000 BF
|
||||
99 conv 448 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 448 0.009 BF
|
||||
100 conv 448/ 448 3 x 3/ 1 10 x 10 x 448 -> 10 x 10 x 448 0.001 BF
|
||||
101 conv 96 1 x 1/ 1 10 x 10 x 448 -> 10 x 10 x 96 0.009 BF
|
||||
102 dropout p = 0.200 9600 -> 9600
|
||||
103 Shortcut Layer: 98, wt = 0, wn = 0, outputs: 10 x 10 x 96 0.000 BF
|
||||
104 conv 448 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 448 0.009 BF
|
||||
105 conv 448/ 448 3 x 3/ 1 10 x 10 x 448 -> 10 x 10 x 448 0.001 BF
|
||||
106 conv 96 1 x 1/ 1 10 x 10 x 448 -> 10 x 10 x 96 0.009 BF
|
||||
107 dropout p = 0.200 9600 -> 9600
|
||||
108 Shortcut Layer: 103, wt = 0, wn = 0, outputs: 10 x 10 x 96 0.000 BF
|
||||
109 max 3x 3/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.000 BF
|
||||
110 route 108 -> 10 x 10 x 96
|
||||
111 max 5x 5/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.000 BF
|
||||
112 route 108 -> 10 x 10 x 96
|
||||
113 max 9x 9/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.001 BF
|
||||
114 route 113 111 109 108 -> 10 x 10 x 384
|
||||
115 conv 96 1 x 1/ 1 10 x 10 x 384 -> 10 x 10 x 96 0.007 BF
|
||||
116 conv 96/ 96 5 x 5/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.000 BF
|
||||
117 conv 96 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.002 BF
|
||||
118 conv 96/ 96 5 x 5/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.000 BF
|
||||
119 conv 96 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 96 0.002 BF
|
||||
120 conv 255 1 x 1/ 1 10 x 10 x 96 -> 10 x 10 x 255 0.005 BF
|
||||
121 yolo
|
||||
[yolo] params: iou loss: ciou (4), iou_norm: 0.07, obj_norm: 1.00, cls_norm: 1.00, delta_norm: 1.00, scale_x_y: 1.00
|
||||
nms_kind: greedynms (1), beta = 0.600000
|
||||
122 route 115 -> 10 x 10 x 96
|
||||
123 upsample 2x 10 x 10 x 96 -> 20 x 20 x 96
|
||||
124 route 123 80 -> 20 x 20 x 144
|
||||
125 conv 144/ 144 5 x 5/ 1 20 x 20 x 144 -> 20 x 20 x 144 0.003 BF
|
||||
126 conv 144 1 x 1/ 1 20 x 20 x 144 -> 20 x 20 x 144 0.017 BF
|
||||
127 conv 144/ 144 5 x 5/ 1 20 x 20 x 144 -> 20 x 20 x 144 0.003 BF
|
||||
128 conv 144 1 x 1/ 1 20 x 20 x 144 -> 20 x 20 x 144 0.017 BF
|
||||
129 conv 255 1 x 1/ 1 20 x 20 x 144 -> 20 x 20 x 255 0.029 BF
|
||||
130 yolo
|
||||
[yolo] params: iou loss: ciou (4), iou_norm: 0.07, obj_norm: 1.00, cls_norm: 1.00, delta_norm: 1.00, scale_x_y: 1.00
|
||||
nms_kind: greedynms (1), beta = 0.600000
|
||||
Total BFLOPS 0.725
|
||||
avg_outputs = 120982
|
||||
Allocate additional workspace_size = 0.31 MB
|
||||
Loading weights from model/yolo-fastest-1_final.weights...
|
||||
seen 64, trained: 16000 K-images (250 Kilo-batches_64)
|
||||
Done! Loaded 131 layers from weights-file
|
||||
|
||||
calculation mAP (mean average precision)...
|
||||
Detection layer: 121 - type = 28
|
||||
Detection layer: 130 - type = 28
|
||||
4952
|
||||
detections_count = 664785, unique_truth_count = 36335
|
||||
class_id = 0, name = person, ap = 53.92% (TP = 4976, FP = 5767)
|
||||
class_id = 1, name = bicycle, ap = 25.29% (TP = 81, FP = 105)
|
||||
class_id = 2, name = car, ap = 30.59% (TP = 666, FP = 1092)
|
||||
class_id = 3, name = motorcycle, ap = 47.05% (TP = 157, FP = 174)
|
||||
class_id = 4, name = airplane, ap = 63.87% (TP = 87, FP = 63)
|
||||
class_id = 5, name = bus, ap = 60.84% (TP = 160, FP = 90)
|
||||
class_id = 6, name = train, ap = 72.50% (TP = 124, FP = 59)
|
||||
class_id = 7, name = truck, ap = 30.67% (TP = 126, FP = 177)
|
||||
class_id = 8, name = boat, ap = 20.35% (TP = 111, FP = 233)
|
||||
class_id = 9, name = traffic light, ap = 17.36% (TP = 147, FP = 311)
|
||||
class_id = 10, name = fire hydrant, ap = 63.01% (TP = 54, FP = 22)
|
||||
class_id = 11, name = stop sign, ap = 54.51% (TP = 38, FP = 25)
|
||||
class_id = 12, name = parking meter, ap = 39.62% (TP = 24, FP = 12)
|
||||
class_id = 13, name = bench, ap = 16.95% (TP = 67, FP = 120)
|
||||
class_id = 14, name = bird, ap = 22.58% (TP = 104, FP = 185)
|
||||
class_id = 15, name = cat, ap = 73.95% (TP = 129, FP = 112)
|
||||
class_id = 16, name = dog, ap = 58.90% (TP = 118, FP = 128)
|
||||
class_id = 17, name = horse, ap = 57.27% (TP = 153, FP = 120)
|
||||
class_id = 18, name = sheep, ap = 45.20% (TP = 185, FP = 305)
|
||||
class_id = 19, name = cow, ap = 48.22% (TP = 191, FP = 212)
|
||||
class_id = 20, name = elephant, ap = 68.17% (TP = 176, FP = 147)
|
||||
class_id = 21, name = bear, ap = 77.67% (TP = 51, FP = 28)
|
||||
class_id = 22, name = zebra, ap = 74.43% (TP = 183, FP = 91)
|
||||
class_id = 23, name = giraffe, ap = 75.02% (TP = 166, FP = 65)
|
||||
class_id = 24, name = backpack, ap = 5.03% (TP = 21, FP = 86)
|
||||
class_id = 25, name = umbrella, ap = 36.33% (TP = 151, FP = 161)
|
||||
class_id = 26, name = handbag, ap = 1.68% (TP = 11, FP = 72)
|
||||
class_id = 27, name = tie, ap = 20.32% (TP = 60, FP = 120)
|
||||
class_id = 28, name = suitcase, ap = 21.99% (TP = 73, FP = 137)
|
||||
class_id = 29, name = frisbee, ap = 46.40% (TP = 57, FP = 60)
|
||||
class_id = 30, name = skis, ap = 19.74% (TP = 60, FP = 153)
|
||||
class_id = 31, name = snowboard, ap = 18.86% (TP = 20, FP = 51)
|
||||
class_id = 32, name = sports ball, ap = 28.16% (TP = 74, FP = 72)
|
||||
class_id = 33, name = kite, ap = 35.39% (TP = 139, FP = 247)
|
||||
class_id = 34, name = baseball bat, ap = 20.85% (TP = 33, FP = 63)
|
||||
class_id = 35, name = baseball glove, ap = 21.76% (TP = 40, FP = 97)
|
||||
class_id = 36, name = skateboard, ap = 36.03% (TP = 79, FP = 112)
|
||||
class_id = 37, name = surfboard, ap = 27.98% (TP = 93, FP = 194)
|
||||
class_id = 38, name = tennis racket, ap = 36.49% (TP = 99, FP = 175)
|
||||
class_id = 39, name = bottle, ap = 16.24% (TP = 170, FP = 327)
|
||||
class_id = 40, name = wine glass, ap = 15.37% (TP = 48, FP = 125)
|
||||
class_id = 41, name = cup, ap = 23.22% (TP = 211, FP = 348)
|
||||
class_id = 42, name = fork, ap = 14.48% (TP = 29, FP = 60)
|
||||
class_id = 43, name = knife, ap = 4.63% (TP = 15, FP = 62)
|
||||
class_id = 44, name = spoon, ap = 3.32% (TP = 9, FP = 27)
|
||||
class_id = 45, name = bowl, ap = 33.69% (TP = 209, FP = 261)
|
||||
class_id = 46, name = banana, ap = 23.40% (TP = 86, FP = 136)
|
||||
class_id = 47, name = apple, ap = 8.21% (TP = 24, FP = 89)
|
||||
class_id = 48, name = sandwich, ap = 33.67% (TP = 56, FP = 80)
|
||||
class_id = 49, name = orange, ap = 22.59% (TP = 77, FP = 137)
|
||||
class_id = 50, name = broccoli, ap = 23.62% (TP = 88, FP = 178)
|
||||
class_id = 51, name = carrot, ap = 10.15% (TP = 55, FP = 159)
|
||||
class_id = 52, name = hot dog, ap = 28.57% (TP = 33, FP = 38)
|
||||
class_id = 53, name = pizza, ap = 51.21% (TP = 129, FP = 148)
|
||||
class_id = 54, name = donut, ap = 30.97% (TP = 116, FP = 184)
|
||||
class_id = 55, name = cake, ap = 32.03% (TP = 99, FP = 155)
|
||||
class_id = 56, name = chair, ap = 18.50% (TP = 304, FP = 568)
|
||||
class_id = 57, name = couch, ap = 48.84% (TP = 125, FP = 156)
|
||||
class_id = 58, name = potted plant, ap = 20.71% (TP = 66, FP = 118)
|
||||
class_id = 59, name = bed, ap = 52.73% (TP = 88, FP = 97)
|
||||
class_id = 60, name = dining table, ap = 27.14% (TP = 224, FP = 334)
|
||||
class_id = 61, name = toilet, ap = 66.39% (TP = 112, FP = 77)
|
||||
class_id = 62, name = tv, ap = 56.32% (TP = 151, FP = 98)
|
||||
class_id = 63, name = laptop, ap = 54.05% (TP = 100, FP = 157)
|
||||
class_id = 64, name = mouse, ap = 44.78% (TP = 46, FP = 44)
|
||||
class_id = 65, name = remote, ap = 7.84% (TP = 28, FP = 102)
|
||||
class_id = 66, name = keyboard, ap = 44.37% (TP = 71, FP = 83)
|
||||
class_id = 67, name = cell phone, ap = 24.25% (TP = 62, FP = 74)
|
||||
class_id = 68, name = microwave, ap = 46.90% (TP = 21, FP = 19)
|
||||
class_id = 69, name = oven, ap = 37.19% (TP = 54, FP = 52)
|
||||
class_id = 70, name = toaster, ap = 10.84% (TP = 0, FP = 0)
|
||||
class_id = 71, name = sink, ap = 34.06% (TP = 81, FP = 98)
|
||||
class_id = 72, name = refrigerator, ap = 46.76% (TP = 57, FP = 45)
|
||||
class_id = 73, name = book, ap = 4.20% (TP = 112, FP = 548)
|
||||
class_id = 74, name = clock, ap = 53.92% (TP = 144, FP = 92)
|
||||
class_id = 75, name = vase, ap = 25.27% (TP = 67, FP = 70)
|
||||
class_id = 76, name = scissors, ap = 21.61% (TP = 7, FP = 10)
|
||||
class_id = 77, name = teddy bear, ap = 47.50% (TP = 90, FP = 56)
|
||||
class_id = 78, name = hair drier, ap = 0.70% (TP = 0, FP = 0)
|
||||
class_id = 79, name = toothbrush, ap = 1.50% (TP = 2, FP = 9)
|
||||
|
||||
for conf_thresh = 0.25, precision = 0.43, recall = 0.35, F1-score = 0.39
|
||||
for conf_thresh = 0.25, TP = 12750, FP = 16864, FN = 23585, average IoU = 31.39 %
|
||||
|
||||
IoU threshold = 50 %, used Area-Under-Curve for each unique Recall
|
||||
mean average precision (mAP@0.50) = 0.343340, or 34.33 %
|
||||
Total Detection Time: 93 Seconds
|
||||
|
||||
@ -0,0 +1,947 @@
|
||||
[net]
|
||||
batch=32
|
||||
subdivisions=1
|
||||
width=320
|
||||
height=320
|
||||
channels=3
|
||||
momentum=0.949
|
||||
decay=0.0005
|
||||
angle=0
|
||||
saturation=1.5
|
||||
exposure=1.5
|
||||
hue=.1
|
||||
|
||||
|
||||
learning_rate=0.001
|
||||
burn_in=4000
|
||||
max_batches=500000
|
||||
policy=steps
|
||||
steps=400000,450000
|
||||
scales=.1,.1
|
||||
|
||||
[convolutional]
|
||||
filters=16
|
||||
size=3
|
||||
pad=1
|
||||
stride=2
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=16
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=16
|
||||
filters=16
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=8
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=16
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=16
|
||||
filters=16
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=8
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=48
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=48
|
||||
filters=48
|
||||
size=3
|
||||
pad=1
|
||||
stride=2
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=16
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=64
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=64
|
||||
filters=64
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=16
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=64
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=64
|
||||
filters=64
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=16
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=64
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=64
|
||||
filters=64
|
||||
size=3
|
||||
pad=1
|
||||
stride=2
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=16
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=96
|
||||
filters=96
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=16
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=96
|
||||
filters=96
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=16
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=96
|
||||
filters=96
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=32
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=192
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=192
|
||||
filters=192
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=32
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=192
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=192
|
||||
filters=192
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=32
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=192
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=192
|
||||
filters=192
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=32
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=192
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=192
|
||||
filters=192
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=32
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=192
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=192
|
||||
filters=192
|
||||
size=3
|
||||
pad=1
|
||||
stride=2
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=48
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=272
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=272
|
||||
filters=272
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=48
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=272
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=272
|
||||
filters=272
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=48
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=272
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=272
|
||||
filters=272
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=48
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=272
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=272
|
||||
filters=272
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=48
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=272
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=272
|
||||
filters=272
|
||||
size=3
|
||||
pad=1
|
||||
stride=2
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=448
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=448
|
||||
filters=448
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=448
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=448
|
||||
filters=448
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=448
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=448
|
||||
filters=448
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=448
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=448
|
||||
filters=448
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=448
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=448
|
||||
filters=448
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
[dropout]
|
||||
probability=.2
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
###############
|
||||
[maxpool]
|
||||
stride=1
|
||||
size=3
|
||||
|
||||
[route]
|
||||
layers=-2
|
||||
|
||||
[maxpool]
|
||||
stride=1
|
||||
size=5
|
||||
|
||||
[route]
|
||||
layers=-4
|
||||
|
||||
[maxpool]
|
||||
stride=1
|
||||
size=9
|
||||
|
||||
[route]
|
||||
layers=-1,-3,-5,-6
|
||||
|
||||
### End SPP ###
|
||||
###############
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=5
|
||||
groups=96
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=5
|
||||
groups=96
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[convolutional]
|
||||
size=1
|
||||
stride=1
|
||||
pad=1
|
||||
filters=255
|
||||
activation=linear
|
||||
|
||||
|
||||
[yolo]
|
||||
mask = 3,4,5
|
||||
anchors = 12, 18, 37, 49, 52,132, 115, 73, 119,199, 242,238
|
||||
classes=80
|
||||
num=6
|
||||
jitter=.15
|
||||
ignore_thresh = .5
|
||||
truth_thresh = 1
|
||||
random=0
|
||||
scale_x_y = 1.0
|
||||
iou_thresh=0.213
|
||||
cls_normalizer=1.0
|
||||
iou_normalizer=0.07
|
||||
iou_loss=ciou
|
||||
nms_kind=greedynms
|
||||
beta_nms=0.6
|
||||
|
||||
[route]
|
||||
layers = -7
|
||||
|
||||
[upsample]
|
||||
stride = 2
|
||||
|
||||
[route]
|
||||
layers=-1,80
|
||||
|
||||
[convolutional]
|
||||
filters=144
|
||||
size=5
|
||||
groups=144
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=144
|
||||
size=1
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=144
|
||||
size=5
|
||||
groups=144
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=144
|
||||
size=1
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
size=1
|
||||
stride=1
|
||||
pad=1
|
||||
filters=255
|
||||
activation=linear
|
||||
|
||||
|
||||
[yolo]
|
||||
mask = 0,1,2
|
||||
anchors = 12, 18, 37, 49, 52,132, 115, 73, 119,199, 242,238
|
||||
classes=80
|
||||
num=6
|
||||
jitter=.15
|
||||
ignore_thresh = .5
|
||||
truth_thresh = 1
|
||||
random=0
|
||||
scale_x_y = 1.00
|
||||
iou_thresh=0.213
|
||||
cls_normalizer=1.0
|
||||
iou_normalizer=0.07
|
||||
iou_loss=ciou
|
||||
nms_kind=greedynms
|
||||
beta_nms=0.6
|
||||
|
||||
Binary file not shown.
@ -0,0 +1,946 @@
|
||||
[net]
|
||||
batch=32
|
||||
subdivisions=1
|
||||
width=320
|
||||
height=320
|
||||
channels=3
|
||||
momentum=0.949
|
||||
decay=0.0005
|
||||
angle=0
|
||||
saturation=1.5
|
||||
exposure=1.5
|
||||
hue=.1
|
||||
|
||||
|
||||
learning_rate=0.001
|
||||
burn_in=4000
|
||||
max_batches=500000
|
||||
policy=steps
|
||||
steps=400000,450000
|
||||
scales=.1,.1
|
||||
|
||||
[convolutional]
|
||||
filters=8
|
||||
size=3
|
||||
pad=1
|
||||
stride=2
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=8
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=8
|
||||
filters=8
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=4
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=8
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=8
|
||||
filters=8
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=4
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=24
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=24
|
||||
filters=24
|
||||
size=3
|
||||
pad=1
|
||||
stride=2
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=8
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=32
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=32
|
||||
filters=32
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=8
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=32
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=32
|
||||
filters=32
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=8
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=32
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=32
|
||||
filters=32
|
||||
size=3
|
||||
pad=1
|
||||
stride=2
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=8
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=48
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=48
|
||||
filters=48
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=8
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=48
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=48
|
||||
filters=48
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=8
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=48
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=48
|
||||
filters=48
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=16
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=96
|
||||
filters=96
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=16
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=96
|
||||
filters=96
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=16
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=96
|
||||
filters=96
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=16
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=96
|
||||
filters=96
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=16
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=96
|
||||
filters=96
|
||||
size=3
|
||||
pad=1
|
||||
stride=2
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=24
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=136
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=136
|
||||
filters=136
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=24
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=136
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=136
|
||||
filters=136
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=24
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=136
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=136
|
||||
filters=136
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=24
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=136
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=136
|
||||
filters=136
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=24
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=136
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=136
|
||||
filters=136
|
||||
size=3
|
||||
pad=1
|
||||
stride=2
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=48
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[convolutional]
|
||||
filters=224
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=224
|
||||
filters=224
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=48
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=224
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=224
|
||||
filters=224
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=48
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=224
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=224
|
||||
filters=224
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=48
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=224
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=224
|
||||
filters=224
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=48
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=224
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
groups=224
|
||||
filters=224
|
||||
size=3
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=48
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
[dropout]
|
||||
probability=.15
|
||||
|
||||
[shortcut]
|
||||
from=-5
|
||||
activation=linear
|
||||
###############
|
||||
[maxpool]
|
||||
stride=1
|
||||
size=3
|
||||
|
||||
[route]
|
||||
layers=-2
|
||||
|
||||
[maxpool]
|
||||
stride=1
|
||||
size=5
|
||||
|
||||
[route]
|
||||
layers=-4
|
||||
|
||||
[maxpool]
|
||||
stride=1
|
||||
size=9
|
||||
|
||||
[route]
|
||||
layers=-1,-3,-5,-6
|
||||
|
||||
### End SPP ###
|
||||
###############
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=0
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=5
|
||||
groups=96
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=5
|
||||
groups=96
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=96
|
||||
size=1
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
|
||||
[convolutional]
|
||||
size=1
|
||||
stride=1
|
||||
pad=1
|
||||
filters=255
|
||||
activation=linear
|
||||
|
||||
|
||||
[yolo]
|
||||
mask = 3,4,5
|
||||
anchors = 12, 18, 37, 49, 52,132, 115, 73, 119,199, 242,238
|
||||
classes=80
|
||||
num=6
|
||||
jitter=.15
|
||||
ignore_thresh = .5
|
||||
truth_thresh = 1
|
||||
random=0
|
||||
scale_x_y = 1.0
|
||||
iou_thresh=0.213
|
||||
cls_normalizer=1.0
|
||||
iou_normalizer=0.07
|
||||
iou_loss=ciou
|
||||
nms_kind=greedynms
|
||||
beta_nms=0.6
|
||||
|
||||
[route]
|
||||
layers = -7
|
||||
|
||||
[upsample]
|
||||
stride = 2
|
||||
|
||||
[route]
|
||||
layers=-1,80
|
||||
|
||||
[convolutional]
|
||||
filters=120
|
||||
size=5
|
||||
groups=120
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=120
|
||||
size=1
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
filters=120
|
||||
size=5
|
||||
groups=120
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=leaky
|
||||
|
||||
[convolutional]
|
||||
filters=120
|
||||
size=1
|
||||
stride=1
|
||||
pad=1
|
||||
batch_normalize=1
|
||||
activation=linear
|
||||
|
||||
[convolutional]
|
||||
size=1
|
||||
stride=1
|
||||
pad=1
|
||||
filters=255
|
||||
activation=linear
|
||||
|
||||
|
||||
[yolo]
|
||||
mask = 0,1,2
|
||||
anchors = 12, 18, 37, 49, 52,132, 115, 73, 119,199, 242,238
|
||||
classes=80
|
||||
num=6
|
||||
jitter=.15
|
||||
ignore_thresh = .5
|
||||
truth_thresh = 1
|
||||
random=0
|
||||
scale_x_y = 1.00
|
||||
iou_thresh=0.213
|
||||
cls_normalizer=1.0
|
||||
iou_normalizer=0.07
|
||||
iou_loss=ciou
|
||||
nms_kind=greedynms
|
||||
beta_nms=0.6
|
||||
|
||||
Binary file not shown.
@ -0,0 +1,648 @@
|
||||
/**
|
||||
********************************************************************
|
||||
*
|
||||
* @copyright (c) 2023 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <iostream>
|
||||
#include <dji_logger.h>
|
||||
#include "test_liveview_entry.hpp"
|
||||
#include "dji_liveview_object_detection.hpp"
|
||||
#include "dji_payload_camera.h"
|
||||
#include "dji_high_speed_data_channel.h"
|
||||
#include <string>
|
||||
#include <vector>
|
||||
#include "dji_typedef.h"
|
||||
#include <chrono>
|
||||
#include <thread>
|
||||
#include <fstream>
|
||||
#include <ctime>
|
||||
#include <sstream>
|
||||
#include "dji_open_ar.h"
|
||||
#include <queue>
|
||||
|
||||
#ifdef OPEN_CV_INSTALLED
|
||||
#include <opencv2/opencv.hpp>
|
||||
#include <opencv2/dnn.hpp>
|
||||
#include <opencv2/core.hpp>
|
||||
#include "image_processor_yolovfastest.hpp"
|
||||
#endif
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define YOLO_LABLES_NUM 76
|
||||
#define INVALID_CLASS_NUM 4
|
||||
|
||||
static const char* s_classLables[] = {
|
||||
"person", "bicycle", "car", "motorbike",
|
||||
"aeroplane", "bus", "train", "truck",
|
||||
"boat", "traffic light", "fire hydrant", "stop sign",
|
||||
"parking meter", "bench", "bird", "cat",
|
||||
"dog", "horse", "sheep", "cow",
|
||||
"elephant", "bear", "zebra", "giraffe",
|
||||
"backpack", "umbrella", "handbag", "tie",
|
||||
"suitcase", "frisbee", "skis", "snowboard",
|
||||
"sports ball", "kite", "baseball bat", "baseball glove",
|
||||
"skateboard", "surfboard", "tennis racket", "bottle",
|
||||
"wine glass", "cup", "fork", "knife",
|
||||
"spoon", "bowl", "banana", "apple",
|
||||
"sandwich", "orange", "broccoli", "carrot",
|
||||
"hot dog", "pizza", "donut", "cake",
|
||||
"chair", "sofa", "pottedplant", "bed",
|
||||
"diningtable", "toilet", "tvmonitor", "laptop",
|
||||
"mouse", "remote", "keyboard", "cell phone",
|
||||
"microwave", "oven", "toaster", "sink",
|
||||
"refrigerator", "book", "clock", "vase",
|
||||
"scissors", "teddy bear", "hair drier", "toothbrush",
|
||||
};
|
||||
|
||||
static const char* s_invalidLables[] = {
|
||||
"XXX", "WW", "YYYYYYYYYYY", "ZZZZZZZZ"
|
||||
};
|
||||
|
||||
static std::ofstream outFileH264;
|
||||
static std::ofstream outFileYUV;
|
||||
static std::string getCurrentTimestamp();
|
||||
static void outH264Tofile(const uint8_t *buf, int32_t len);
|
||||
static void outYUVTofile(const uint8_t *buf, int32_t len);
|
||||
static void DjiLiveview_RcvImageCallback(E_DjiLiveViewCameraPosition position, const uint8_t *buf, uint32_t len ,T_DjiLiveviewImageInfo imageInfo);
|
||||
static void DjiLiveview_EncoderUseCallback(const uint8_t *buf, uint32_t len);
|
||||
|
||||
#ifdef OPEN_CV_INSTALLED
|
||||
static ImageProcessorYolovFastest processor("YOLOvFastest");
|
||||
static std::queue<cv::Mat> s_imageQueue;
|
||||
static std::queue<T_DjiLiveViewStandardMetaData *> s_metaQueue;
|
||||
static void *DjiLiveview_ObjectDetectionThread(void *arg);
|
||||
T_DjiTaskHandle s_procThreadHandle;
|
||||
T_DjiMutexHandle s_metaQueueMutexHandle;
|
||||
T_DjiMutexHandle s_imageQueueMutexHandle;
|
||||
#endif
|
||||
|
||||
void DjiUser_InitOpenAr(T_DjiOpenArPoint* point)
|
||||
{
|
||||
point->uuid = 1;
|
||||
point->style_id = 10;
|
||||
point->resource_id = 0;
|
||||
point->is_always_in_edge = 1;
|
||||
|
||||
point->coordinate = {113.939467, 22.526366, 1.0};
|
||||
|
||||
point->text_attr.is_show = 1;
|
||||
memcpy(point->text_attr.text, "测试文本", sizeof("测试文本"));
|
||||
|
||||
point->icon_attr = {0, 1, 33445566};
|
||||
point->touch_attr = {1, {0.0, 0.0, 1.0}};
|
||||
}
|
||||
|
||||
void ArRrefleshAll()
|
||||
{
|
||||
USER_LOG_INFO("do ar reflesh all");
|
||||
uint8_t buf[1024];
|
||||
memset(buf, 0, sizeof(buf));
|
||||
|
||||
T_DjiOpenArCircle* circle = (T_DjiOpenArCircle*)buf;
|
||||
circle->ids = {50, 10};
|
||||
circle->center = {113.939467, 22.526366, 11.};
|
||||
circle->radius = 2;
|
||||
circle->normal_vector = {0, 0, 3};
|
||||
circle->face = {0, 1, 1, 1};
|
||||
circle->stroke = {1, 1, 1, 1, 1, 1};
|
||||
DjiLiveview_ArSetCircle(circle);
|
||||
}
|
||||
|
||||
void DjiUser_RunOpenArSample()
|
||||
{
|
||||
DjiLiveview_ArRegRefleshAllCallback(ArRrefleshAll);
|
||||
bool exit = false;
|
||||
while (!exit)
|
||||
{
|
||||
std::cout
|
||||
<< "\n"
|
||||
<< "| Available commands: \n"
|
||||
<< "| [0] Set Point - draw tow points\n"
|
||||
<< "| [1] Update point - append tow points\n"
|
||||
<< "| [2] Delete point - delete tow point\n"
|
||||
<< "| [3] Clear point- clear all points\n"
|
||||
<< "| [4] Set line - draw a line with five points.\n"
|
||||
<< "| [5] Update line - add a line with tow points.\n"
|
||||
<< "| [6] Delete line - delete the line drawn in the [5] step.\n"
|
||||
<< "| [7] Clear line - clear lines\n"
|
||||
<< "| [8] Set polygon - draw a cuboid\n"
|
||||
<< "| [9] Update polygon - draw a triangular prism\n"
|
||||
<< "| [a] Delete polygon - delete the triangular prism\n"
|
||||
<< "| [b] Clear polygon - clear polygon\n"
|
||||
<< "| [c] Set circle - draw a circle\n"
|
||||
<< "| [d] Update circle - add a circle\n"
|
||||
<< "| [e] Delete circle - delete a circle\n"
|
||||
<< "| [f] Clear circle - clear circle\n"
|
||||
<< "| [q] Exit\n"
|
||||
<< std::endl;
|
||||
|
||||
char inputChar;
|
||||
std::cin >> inputChar;
|
||||
uint8_t buf[1024];
|
||||
memset(buf, 0, sizeof(buf));
|
||||
|
||||
T_DjiOpenArPoint point;
|
||||
DjiUser_InitOpenAr(&point);
|
||||
|
||||
T_DjiOpenArPointArray* point_array = (T_DjiOpenArPointArray*)buf;
|
||||
T_DjiOpenArLine* line = (T_DjiOpenArLine*)buf;
|
||||
T_DjiOpenArPolygon* polygon = (T_DjiOpenArPolygon*)buf;
|
||||
T_DjiOpenArCircle* circle = (T_DjiOpenArCircle*)buf;
|
||||
T_DjiOpenArPivotAxis* pivot = (T_DjiOpenArPivotAxis*)buf;
|
||||
|
||||
T_DjiOpenArDeletePointEntry* delete_point_entry = (T_DjiOpenArDeletePointEntry*)buf;
|
||||
T_DjiOpenArDeleteLineEntry* delete_line_entry = (T_DjiOpenArDeleteLineEntry*)buf;
|
||||
T_DjiOpenArDeletePolygonEntry* delete_polygon_entry = (T_DjiOpenArDeletePolygonEntry*)buf;
|
||||
T_DjiOpenArDeleteCircleEntry* delete_circle_entry = (T_DjiOpenArDeleteCircleEntry*)buf;
|
||||
T_DjiOpenArDeletePovixAxisEntry* delete_povix_entry = (T_DjiOpenArDeletePovixAxisEntry*)buf;
|
||||
|
||||
switch(inputChar) {
|
||||
case '0':
|
||||
point_array->len = 2;
|
||||
|
||||
point.uuid = 1;
|
||||
memcpy(point.text_attr.text, "测试文本", sizeof("测试文本"));
|
||||
memcpy(&point_array->points[0], &point, sizeof(point));
|
||||
|
||||
point.uuid = 2;
|
||||
point.coordinate.altitude = 2.0f;
|
||||
memcpy(point.text_attr.text, "test text", sizeof("test text"));
|
||||
memcpy(&point_array->points[1], &point, sizeof(point));
|
||||
|
||||
DjiLiveview_ArSetPoint(point_array);
|
||||
break;
|
||||
case '1':
|
||||
point_array->len = 2;
|
||||
point.uuid = 3;
|
||||
point.coordinate.altitude = 3.0f;
|
||||
memcpy(point.text_attr.text, "point update", sizeof("point update"));
|
||||
memcpy(&point_array->points[0], &point, sizeof(point));
|
||||
|
||||
point.uuid = 4;
|
||||
point.coordinate.altitude = 4.0f;
|
||||
memcpy(&point_array->points[1], &point, sizeof(point));
|
||||
DjiLiveview_ArUpdatePoint(point_array);
|
||||
|
||||
break;
|
||||
case '2':
|
||||
delete_point_entry->resource_id = 0;
|
||||
delete_point_entry->uuid_len = 2;
|
||||
delete_point_entry->uuid_array[0] = 1;
|
||||
delete_point_entry->uuid_array[1] = 2;
|
||||
DjiLiveview_ArDeletePoint(delete_point_entry);
|
||||
break;
|
||||
|
||||
case '3':
|
||||
DjiLiveview_ArClearPoint(0);
|
||||
break;
|
||||
|
||||
case '4':
|
||||
line->ids.uuid = 10;
|
||||
line->ids.style_id = 10;
|
||||
line->point_array.len = 5;
|
||||
|
||||
point.uuid = 11;
|
||||
point.coordinate.altitude = 4.0f;
|
||||
memcpy(&line->point_array.points[0], &point, sizeof(point));
|
||||
|
||||
point.uuid = 12;
|
||||
point.coordinate.altitude = 5.0f;
|
||||
memcpy(&line->point_array.points[1], &point, sizeof(point));
|
||||
|
||||
point.uuid = 13;
|
||||
point.coordinate.altitude = 6.0f;
|
||||
memcpy(&line->point_array.points[2], &point, sizeof(point));
|
||||
|
||||
point.uuid = 14;
|
||||
point.coordinate.altitude = 7.0f;
|
||||
memcpy(&line->point_array.points[3], &point, sizeof(point));
|
||||
|
||||
point.uuid = 15;
|
||||
point.coordinate.altitude = 8.0f;
|
||||
memcpy(&line->point_array.points[4], &point, sizeof(point));
|
||||
|
||||
DjiLiveview_ArSetLine(line);
|
||||
break;
|
||||
|
||||
case '5':
|
||||
line->ids.uuid = 11;
|
||||
line->ids.style_id = 10;
|
||||
line->point_array.len = 2;
|
||||
|
||||
point.uuid = 16;
|
||||
point.coordinate.altitude = 9.0f;
|
||||
memcpy(&line->point_array.points[0], &point, sizeof(point));
|
||||
|
||||
point.uuid = 17;
|
||||
point.coordinate.altitude = 10.0f;
|
||||
memcpy(&line->point_array.points[1], &point, sizeof(point));
|
||||
|
||||
DjiLiveview_ArUpdateLine(line);
|
||||
break;
|
||||
|
||||
case '6':
|
||||
delete_line_entry[0].uuid = 10;
|
||||
DjiLiveview_ArDeleteLine(delete_line_entry, 1);
|
||||
break;
|
||||
|
||||
case '7':
|
||||
DjiLiveview_ArClearLine();
|
||||
break;
|
||||
|
||||
case '8':
|
||||
polygon->ids = {40, 11};
|
||||
polygon->face = {0, 1, 1, 1};
|
||||
polygon->stroke = {1, 1, 1, 1, 1, 1};
|
||||
polygon->normal_vector = {0, 0, 6};
|
||||
polygon->point_array.len = 4;
|
||||
point.uuid = 41;
|
||||
point.coordinate.altitude = 1;
|
||||
point.coordinate.longitude = 113.939438538;
|
||||
point.coordinate.latitude = 22.5263937487;
|
||||
memcpy(&polygon->point_array.points[0], &point, sizeof(point));
|
||||
|
||||
point.uuid = 42;
|
||||
point.coordinate.longitude = 113.939496338;
|
||||
point.coordinate.latitude = 22.5263937487;
|
||||
memcpy(&polygon->point_array.points[1], &point, sizeof(point));
|
||||
|
||||
point.uuid = 43;
|
||||
point.coordinate.longitude = 113.939496338;
|
||||
point.coordinate.latitude = 22.5263397487;
|
||||
memcpy(&polygon->point_array.points[2], &point, sizeof(point));
|
||||
|
||||
point.uuid = 44;
|
||||
point.coordinate.longitude = 113.939438538;
|
||||
point.coordinate.latitude = 22.5263397487;
|
||||
memcpy(&polygon->point_array.points[3], &point, sizeof(point));
|
||||
|
||||
DjiLiveview_ArSetPolygon(polygon);
|
||||
break;
|
||||
|
||||
case '9':
|
||||
polygon->ids = {45, 11};
|
||||
polygon->face = {0, 1, 1, 1};
|
||||
polygon->stroke = {1, 1, 1, 1, 1, 1};
|
||||
polygon->normal_vector = {0, 0, 4};
|
||||
polygon->point_array.len = 3;
|
||||
point.uuid = 46;
|
||||
point.coordinate.altitude = 12;
|
||||
point.coordinate.longitude = 113.939438538;
|
||||
point.coordinate.latitude = 22.5263937487;
|
||||
memcpy(&polygon->point_array.points[0], &point, sizeof(point));
|
||||
|
||||
point.uuid = 47;
|
||||
point.coordinate.longitude = 113.939496338;
|
||||
point.coordinate.latitude = 22.5263937487;
|
||||
memcpy(&polygon->point_array.points[1], &point, sizeof(point));
|
||||
|
||||
point.uuid = 48;
|
||||
point.coordinate.longitude = 113.939496338;
|
||||
point.coordinate.latitude = 22.5263397487;
|
||||
memcpy(&polygon->point_array.points[2], &point, sizeof(point));
|
||||
DjiLiveview_ArUpdatePolygon(polygon);
|
||||
|
||||
break;
|
||||
case 'a':
|
||||
delete_polygon_entry->uuid = 40;
|
||||
DjiLiveview_ArDeletePolygon(delete_polygon_entry, 1);
|
||||
break;
|
||||
|
||||
case 'b':
|
||||
DjiLiveview_ArClearPolygon();
|
||||
break;
|
||||
|
||||
case 'c':
|
||||
circle->ids = {50, 10};
|
||||
circle->center = {113.939467, 22.526366, 11.};
|
||||
circle->radius = 3;
|
||||
circle->normal_vector = {0, 0, 3};
|
||||
circle->face = {0, 1, 1, 1};
|
||||
circle->stroke = {1, 1, 1, 1, 1, 1};
|
||||
DjiLiveview_ArSetCircle(circle);
|
||||
break;
|
||||
|
||||
case 'd':
|
||||
circle->ids = {51, 11};
|
||||
circle->center = {113.939467, 22.526366, 8.};
|
||||
circle->radius = 4;
|
||||
circle->normal_vector = {0, 0, 5};
|
||||
circle->face = {1, 1, 1, 1};
|
||||
circle->stroke = {1, 1, 1, 1, 1, 1};
|
||||
DjiLiveview_ArUpdateCircle(circle);
|
||||
break;
|
||||
|
||||
case 'e':
|
||||
delete_circle_entry->uuid = 50;
|
||||
DjiLiveview_ArDeleteCircle(delete_circle_entry, 1);
|
||||
break;
|
||||
|
||||
case 'f':
|
||||
DjiLiveview_ArClearCircle();
|
||||
break;
|
||||
case 'q':
|
||||
exit = true;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void DjiUser_RunCameraAiDetectionSample()
|
||||
{
|
||||
int pos = 1;
|
||||
int mediaSource = 0; //support 0(app liveview)/1(1080p)/7(4k) for H30 camera
|
||||
char isQuit;
|
||||
E_DjiLiveViewCameraPosition CameraPostion;
|
||||
E_DjiLiveViewCameraSource MediaResource;
|
||||
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
|
||||
if (pos < 1 || pos > 3 || (mediaSource != 0 &&mediaSource != 1 && mediaSource != 7))
|
||||
{
|
||||
USER_LOG_ERROR("invalid param");
|
||||
return;
|
||||
}
|
||||
|
||||
std::string timestamp = getCurrentTimestamp();
|
||||
|
||||
std::string h264FileName = "output_" + timestamp + ".h264";
|
||||
outFileH264.open(h264FileName, std::ios::out | std::ios::binary | std::ios::app);
|
||||
if (!outFileH264) {
|
||||
std::cerr << "cant open " << h264FileName << std::endl;
|
||||
}
|
||||
|
||||
#ifdef OPEN_CV_INSTALLED
|
||||
osalHandler->MutexCreate(&s_metaQueueMutexHandle);
|
||||
osalHandler->MutexCreate(&s_imageQueueMutexHandle);
|
||||
osalHandler->TaskCreate("objectDetectionTask",DjiLiveview_ObjectDetectionThread,1024*1024,NULL, &s_procThreadHandle);
|
||||
if (processor.Init() != 0) {
|
||||
std::cerr << "Failed to initialize the processor." << std::endl;
|
||||
return ;
|
||||
}
|
||||
#endif
|
||||
|
||||
CameraPostion = static_cast<E_DjiLiveViewCameraPosition>(pos);
|
||||
MediaResource = static_cast<E_DjiLiveViewCameraSource>(mediaSource);
|
||||
T_DjiReturnCode returnCode;
|
||||
const T_DjiDataChannelBandwidthProportionOfHighspeedChannel bandwidthProportionOfHighspeedChannel =
|
||||
{10, 60, 30};
|
||||
|
||||
returnCode = DjiHighSpeedDataChannel_SetBandwidthProportion(bandwidthProportionOfHighspeedChannel);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Liveview init failed, HighSpeed channel init error: 0x%08llX", returnCode);
|
||||
return;
|
||||
}
|
||||
USER_LOG_INFO("step 1: init liveview");
|
||||
|
||||
returnCode = DjiLiveview_Init();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Liveview init faild, ret: 0x%08llX", returnCode);
|
||||
goto init_failed;
|
||||
}
|
||||
|
||||
#ifdef OPEN_CV_INSTALLED
|
||||
returnCode = DjiLiveview_RegUserAiTargetLableList(YOLO_LABLES_NUM, s_classLables);
|
||||
#else
|
||||
returnCode = DjiLiveview_RegUserAiTargetLableList(INVALID_CLASS_NUM, s_invalidLables);
|
||||
#endif
|
||||
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Reg ai target lable faild, ret: 0x%08llX", returnCode);
|
||||
goto init_failed;
|
||||
}
|
||||
USER_LOG_INFO("step 2: reg encoder callback");
|
||||
|
||||
returnCode = DjiLiveview_RegEncoderCallback(DjiLiveview_EncoderUseCallback);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR( "reg Yuv Encoder callback faild, ret: 0x%08llX", returnCode);
|
||||
goto reg_encoder_callback_failed;
|
||||
}
|
||||
USER_LOG_INFO("step 3:start yuv stream");
|
||||
|
||||
returnCode = DjiLiveview_StartImageStream(CameraPostion, MediaResource,
|
||||
PIXFMT_RGB_PACKED ,DjiLiveview_RcvImageCallback);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR( "start to subscribe YUV stream failed, ret: 0x%08llX", returnCode);
|
||||
goto start_yuv_stream_failed;
|
||||
}
|
||||
USER_LOG_INFO("codec sample start ...");
|
||||
|
||||
while (true) {
|
||||
std::cin >> isQuit;
|
||||
if (isQuit == 'q' || isQuit == 'Q') {
|
||||
break;
|
||||
}
|
||||
}
|
||||
USER_LOG_INFO("codec sample end");
|
||||
|
||||
DjiLiveview_UnregUserAiTargetLableList();
|
||||
start_yuv_stream_failed:
|
||||
returnCode = DjiLiveview_StopImageStream(CameraPostion, MediaResource);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR( "stop subscrib YUV stream failed, ret: 0x%08llX", returnCode);
|
||||
}
|
||||
|
||||
reg_encoder_callback_failed:
|
||||
returnCode = DjiLiveview_UnregEncoderCallback();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR( "unreg encoder callback failed, ret: 0x%08llX", returnCode);
|
||||
}
|
||||
|
||||
init_failed:
|
||||
returnCode = DjiLiveview_Deinit();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR( "deinit liveview failed, ret: 0x%08llX", returnCode);
|
||||
}
|
||||
outFileH264.close();
|
||||
outFileYUV.close();
|
||||
|
||||
#ifdef OPEN_CV_INSTALLED
|
||||
osalHandler->TaskDestroy(s_procThreadHandle);
|
||||
osalHandler->MutexDestroy(s_imageQueueMutexHandle);
|
||||
osalHandler->MutexDestroy(s_metaQueueMutexHandle);
|
||||
|
||||
while(!s_imageQueue.empty()){
|
||||
s_imageQueue.pop();
|
||||
}
|
||||
while(!s_metaQueue.empty()) {
|
||||
s_metaQueue.pop();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
static std::string getCurrentTimestamp() {
|
||||
std::time_t now = std::time(nullptr);
|
||||
std::tm* now_tm = std::localtime(&now);
|
||||
|
||||
std::ostringstream oss;
|
||||
oss << (now_tm->tm_year + 1900)
|
||||
<< (now_tm->tm_mon + 1)
|
||||
<< now_tm->tm_mday
|
||||
<< now_tm->tm_hour
|
||||
<< now_tm->tm_min;
|
||||
|
||||
return oss.str();
|
||||
}
|
||||
static void outH264Tofile(const uint8_t *buf, int32_t len) {
|
||||
if (!outFileH264) {
|
||||
USER_LOG_ERROR( "output.h264 is not open");
|
||||
return;
|
||||
}
|
||||
outFileH264.write(reinterpret_cast<const char *>(buf), len);
|
||||
}
|
||||
|
||||
static void outYUVTofile(const uint8_t *buf, int32_t len) {
|
||||
if (!outFileYUV) {
|
||||
USER_LOG_ERROR( "outyuv.h264 is not open");
|
||||
return;
|
||||
}
|
||||
outFileYUV.write(reinterpret_cast<const char *>(buf), len);
|
||||
}
|
||||
|
||||
static void DjiLiveview_RcvImageCallback(E_DjiLiveViewCameraPosition position, const uint8_t *buf, uint32_t len, T_DjiLiveviewImageInfo imageInfo)
|
||||
{
|
||||
T_DjiReturnCode DjiStat;
|
||||
uint32_t OutPutLen;
|
||||
std::vector<T_DjiLiveViewBoundingBox> bounding_boxes;
|
||||
USER_LOG_INFO("catch image frame data, image type = %d height = %d, width = %d, frameId = %d, bufferLen= %d",
|
||||
imageInfo.pixFmt ,imageInfo.height, imageInfo.width, imageInfo.frameId, len);
|
||||
T_DjiLiveViewStandardMetaData * metaData = nullptr;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
|
||||
#ifdef OPEN_CV_INSTALLED
|
||||
cv::Mat rgb_image( imageInfo.height, imageInfo.width, CV_8UC3, const_cast<uint8_t*>(buf));
|
||||
cv::Mat rgb_image_copy = rgb_image.clone();
|
||||
|
||||
osalHandler->MutexLock(s_imageQueueMutexHandle);
|
||||
while (s_imageQueue.size() > 30) {
|
||||
USER_LOG_WARN("The image queue is full. Drop this strike.");
|
||||
s_imageQueue.pop();
|
||||
}
|
||||
s_imageQueue.push(rgb_image_copy);
|
||||
osalHandler->MutexUnlock(s_imageQueueMutexHandle);
|
||||
|
||||
osalHandler->MutexLock(s_metaQueueMutexHandle);
|
||||
if (!s_metaQueue.empty()) {
|
||||
metaData = s_metaQueue.front();
|
||||
s_metaQueue.pop();
|
||||
}
|
||||
osalHandler->MutexUnlock(s_metaQueueMutexHandle);
|
||||
|
||||
DjiLiveview_EncodeAFrameToH264(buf, len, imageInfo, metaData);
|
||||
if(metaData != nullptr) free(metaData);
|
||||
|
||||
#else
|
||||
|
||||
size_t size = sizeof(T_DjiLiveViewStandardMetaData) + 3 * sizeof(T_DjiLiveViewBoundingBox);
|
||||
metaData = (T_DjiLiveViewStandardMetaData *)malloc(size);
|
||||
if (!metaData) {
|
||||
fprintf(stderr, "Failed to allocate memory\n");
|
||||
return ;
|
||||
}
|
||||
|
||||
// 初始化 boxCount
|
||||
metaData->boxCount = 4;
|
||||
|
||||
// 初始化每个 T_DjiLiveViewBoundingBox
|
||||
for (int i = 0; i < 4; i++) {
|
||||
metaData->boxData[i].id = i;
|
||||
metaData->boxData[i].type = i;
|
||||
metaData->boxData[i].state = 1;
|
||||
metaData->boxData[i].box.cx = (i+1)*1000;
|
||||
metaData->boxData[i].box.cy = (i+1)*1000;
|
||||
metaData->boxData[i].box.w = 1000;
|
||||
metaData->boxData[i].box.h = 1000;
|
||||
metaData->boxData[i].box.distance = 0;
|
||||
}
|
||||
|
||||
// 打印结果
|
||||
|
||||
DjiLiveview_SendAiMetaToPilot(metaData);
|
||||
|
||||
DjiLiveview_EncodeAFrameToH264(buf, len,imageInfo, metaData);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void DjiLiveview_EncoderUseCallback(const uint8_t *buf, uint32_t len)
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
outH264Tofile(buf, len);
|
||||
returnCode = DjiPayloadCamera_SendVideoStream(buf, len);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("failed to send video to pilot, ret: 0x%08llX", returnCode);
|
||||
}
|
||||
}
|
||||
|
||||
static void* DjiLiveview_ObjectDetectionThread(void *arg) {
|
||||
T_DjiReturnCode DjiStat;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
|
||||
while(1) {
|
||||
#ifdef OPEN_CV_INSTALLED
|
||||
osalHandler->MutexLock(s_imageQueueMutexHandle);
|
||||
if (s_imageQueue.empty()) {
|
||||
osalHandler->MutexUnlock(s_imageQueueMutexHandle);
|
||||
continue;
|
||||
}
|
||||
cv::Mat rgb_image = s_imageQueue.front();
|
||||
s_imageQueue.pop();
|
||||
osalHandler->MutexUnlock(s_imageQueueMutexHandle);
|
||||
cv::Mat bgr_image;
|
||||
cv::cvtColor(rgb_image, bgr_image, cv::COLOR_RGB2BGR);
|
||||
|
||||
std::shared_ptr<cv::Mat> image_ptr = std::make_shared<cv::Mat>(bgr_image);
|
||||
|
||||
|
||||
std::vector<T_DjiLiveViewBoundingBox> bounding_boxes;
|
||||
processor.Process(image_ptr, bounding_boxes);
|
||||
|
||||
T_DjiLiveViewStandardMetaData *metaData = (T_DjiLiveViewStandardMetaData *)malloc(
|
||||
sizeof(T_DjiLiveViewStandardMetaData) + bounding_boxes.size() * sizeof(T_DjiLiveViewBoundingBox));
|
||||
metaData->boxCount = bounding_boxes.size();
|
||||
for (int i = 0; i < bounding_boxes.size(); i++) {
|
||||
metaData->boxData[i] = bounding_boxes[i];
|
||||
}
|
||||
|
||||
DjiLiveview_SendAiMetaToPilot(metaData);
|
||||
|
||||
osalHandler->MutexLock(s_metaQueueMutexHandle);
|
||||
s_metaQueue.push(metaData);
|
||||
osalHandler->MutexUnlock(s_metaQueueMutexHandle);
|
||||
|
||||
#else
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
@ -0,0 +1,41 @@
|
||||
/**
|
||||
********************************************************************
|
||||
*
|
||||
* @copyright (c) 2023 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef TEST_LIVEVIEW_CODEC_H
|
||||
#define TEST_LIVEVIEW_CODEC_H
|
||||
|
||||
#include "dji_liveview.h"
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
void DjiUser_RunCameraAiDetectionSample(void);
|
||||
void DjiUser_RunOpenArSample(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
#endif // TEST_LIVEVIEW_CODEC_H
|
||||
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
@ -0,0 +1,140 @@
|
||||
/**
|
||||
********************************************************************
|
||||
*
|
||||
* @copyright (c) 2023 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
#ifdef OPEN_CV_INSTALLED
|
||||
#include "image_processor_yolovfastest.hpp"
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <sys/time.h>
|
||||
#include <dji_logger.h>
|
||||
#include <fstream>
|
||||
#include <iostream>
|
||||
#include <opencv2/dnn.hpp>
|
||||
#include <opencv2/highgui.hpp>
|
||||
#include <opencv2/imgproc.hpp>
|
||||
#include <sstream>
|
||||
#include <utils/util_misc.h>
|
||||
|
||||
using namespace cv;
|
||||
using namespace dnn;
|
||||
using namespace std;
|
||||
|
||||
int32_t ImageProcessorYolovFastest::Init() {
|
||||
|
||||
memset(cur_file_dir_path_, 0, kCurrentFilePathSizeMax);
|
||||
memset(prototxt_file_dir_path_, 0, kFilePathSizeMax);
|
||||
memset(weights_file_dir_path_, 0, kFilePathSizeMax);
|
||||
|
||||
if (DjiUserUtil_GetCurrentFileDirPath(__FILE__, sizeof(cur_file_dir_path_),
|
||||
cur_file_dir_path_) != 0) {
|
||||
USER_LOG_ERROR("get path failed");
|
||||
return -1;
|
||||
}
|
||||
|
||||
snprintf(prototxt_file_dir_path_, kFilePathSizeMax,
|
||||
"%s/data/yolo-fastest-1.1_coco/yolo-fastest-1.1-xl.cfg",
|
||||
cur_file_dir_path_);
|
||||
snprintf(weights_file_dir_path_, kFilePathSizeMax,
|
||||
"%s/data/yolo-fastest-1.1_coco/yolo-fastest-1.1-xl.weights",
|
||||
cur_file_dir_path_);
|
||||
|
||||
USER_LOG_DEBUG("%s, %s", prototxt_file_dir_path_, weights_file_dir_path_);
|
||||
net_ = readNetFromDarknet(prototxt_file_dir_path_, weights_file_dir_path_);
|
||||
|
||||
if (net_.empty()) {
|
||||
USER_LOG_ERROR("Failed to load network");
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void ImageProcessorYolovFastest::post_process(cv::Mat& frame, const std::vector<cv::Mat>& outs, std::vector<T_DjiLiveViewBoundingBox>& bounding_boxes) {
|
||||
std::vector<int> class_ids;
|
||||
std::vector<float> confidences;
|
||||
std::vector<cv::Rect> boxes;
|
||||
|
||||
for (size_t i = 0; i < outs.size(); ++i) {
|
||||
float* data = (float*)outs[i].data;
|
||||
for (int j = 0; j < outs[i].rows; ++j, data += outs[i].cols) {
|
||||
cv::Mat scores = outs[i].row(j).colRange(5, outs[i].cols);
|
||||
cv::Point classid_point;
|
||||
double confidence;
|
||||
cv::minMaxLoc(scores, 0, &confidence, 0, &classid_point);
|
||||
if (confidence > 0.5) {
|
||||
int cx = (int)(data[0] * frame.cols);
|
||||
int cy = (int)(data[1] * frame.rows);
|
||||
int w = (int)(data[2] * frame.cols);
|
||||
int h = (int)(data[3] * frame.rows);
|
||||
int left = cx - (w >> 1);
|
||||
int top = cy - (h >> 1);
|
||||
class_ids.push_back(classid_point.x);
|
||||
confidences.push_back((float)confidence);
|
||||
boxes.push_back(cv::Rect(left, top, w, h));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
std::vector<int> indices;
|
||||
cv::dnn::NMSBoxes(boxes, confidences, 0.5, 0.4, indices);
|
||||
for (size_t i = 0; i < indices.size(); ++i) {
|
||||
int idx = indices[i];
|
||||
cv::Rect box = boxes[idx];
|
||||
|
||||
T_DjiLiveViewBoundingBox bounding_box;
|
||||
bounding_box.id = i;
|
||||
bounding_box.type = class_ids[idx];
|
||||
bounding_box.state = 1;
|
||||
bounding_box.box.cx = (uint16_t)((box.x + box.width / 2) * 10000 / frame.cols);
|
||||
bounding_box.box.cy = (uint16_t)((box.y + box.height / 2) * 10000 / frame.rows);
|
||||
bounding_box.box.w = (uint16_t)(box.width * 10000 / frame.cols);
|
||||
bounding_box.box.h = (uint16_t)(box.height * 10000 / frame.rows);
|
||||
bounding_box.box.distance = 0;
|
||||
bounding_boxes.push_back(bounding_box);
|
||||
|
||||
std::cout << "Bounding Box " << i << ": "
|
||||
<< "Class ID = " << class_ids[idx] << ", "
|
||||
<< "Confidence = " << confidences[idx] << ", "
|
||||
<< "Box = [" << box.x << ", " << box.y << ", " << box.width << ", " << box.height << "]"
|
||||
<< std::endl;
|
||||
|
||||
cv::rectangle(frame, box, cv::Scalar(0, 255, 0), 2);
|
||||
std::string label = cv::format("ID: %d Conf: %.2f", class_ids[idx], confidences[idx]);
|
||||
cv::putText(frame, label, cv::Point(box.x, box.y - 10), cv::FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(0, 255, 0), 2);
|
||||
}
|
||||
}
|
||||
|
||||
void ImageProcessorYolovFastest::Process(const std::shared_ptr<Image>& image, std::vector<T_DjiLiveViewBoundingBox>& bounding_boxes) {
|
||||
auto detect = [&](cv::Mat& frame, std::vector<cv::Mat>& outs) {
|
||||
cv::Mat blob;
|
||||
cv::dnn::blobFromImage(frame, blob, 1 / 255.0, cv::Size(320, 320), cv::Scalar(0, 0, 0), true, false);
|
||||
net_.setInput(blob);
|
||||
net_.forward(outs, net_.getUnconnectedOutLayersNames());
|
||||
};
|
||||
|
||||
cv::Mat frame = *image;
|
||||
std::vector<cv::Mat> outs;
|
||||
detect(frame, outs);
|
||||
|
||||
post_process(frame, outs, bounding_boxes);
|
||||
}
|
||||
|
||||
#endif
|
||||
@ -0,0 +1,57 @@
|
||||
/**
|
||||
********************************************************************
|
||||
*
|
||||
* @copyright (c) 2023 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
#ifndef __IMAGE_PROCESSOR_DIAPLAY_H__
|
||||
#define __IMAGE_PROCESSOR_DIAPLAY_H__
|
||||
#ifdef OPEN_CV_INSTALLED
|
||||
|
||||
#include <memory>
|
||||
#include "opencv2/opencv.hpp"
|
||||
#include <dji_liveview.h>
|
||||
|
||||
class ImageProcessorYolovFastest {
|
||||
public:
|
||||
ImageProcessorYolovFastest(const std::string& name) : show_name_(name) {}
|
||||
|
||||
~ImageProcessorYolovFastest() {}
|
||||
|
||||
int32_t Init();
|
||||
|
||||
using Image = cv::Mat;
|
||||
void Process(const std::shared_ptr<Image>& image, std::vector<T_DjiLiveViewBoundingBox>& bounding_boxes);
|
||||
std::vector<T_DjiLiveViewBoundingBox> Process(const std::shared_ptr<Image>& image);
|
||||
|
||||
private:
|
||||
std::string show_name_;
|
||||
enum {
|
||||
kFilePathSizeMax = 256,
|
||||
kCurrentFilePathSizeMax = 128,
|
||||
};
|
||||
|
||||
cv::dnn::Net net_;
|
||||
char cur_file_dir_path_[kCurrentFilePathSizeMax];
|
||||
char prototxt_file_dir_path_[kFilePathSizeMax];
|
||||
char weights_file_dir_path_[kFilePathSizeMax];
|
||||
void post_process(cv::Mat& frame, const std::vector<cv::Mat>& outs, std::vector<T_DjiLiveViewBoundingBox>& bounding_boxes);
|
||||
};
|
||||
#endif
|
||||
#endif
|
||||
// #endif
|
||||
0
samples/sample_c++/module_sample/liveview/test_liveview_entry.cpp
Executable file → Normal file
0
samples/sample_c++/module_sample/liveview/test_liveview_entry.cpp
Executable file → Normal file
272
samples/sample_c++/module_sample/perception/test_lidar_entry.cpp
Normal file
272
samples/sample_c++/module_sample/perception/test_lidar_entry.cpp
Normal file
@ -0,0 +1,272 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file test_lidar_entry.cpp
|
||||
* @brief
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "test_lidar_entry.hpp"
|
||||
#include <dirent.h>
|
||||
#include "dji_logger.h"
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
#include <string>
|
||||
#include <ctime>
|
||||
#include <mutex>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#include <mutex>
|
||||
#include <thread>
|
||||
#include <iomanip>
|
||||
#include <sstream>
|
||||
#include <sys/stat.h>
|
||||
#include <sys/types.h>
|
||||
#include <queue>
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define PCD_FILE_DEFAULT_LENGTH (512)
|
||||
#define FRAME_BUFFER_LENGTH (1024 * 1024)
|
||||
#define SUBSCRIBE_DATA_TIME_MS (1000 * 10)
|
||||
#define USER_PERCEPTION_LIRDAR_TASK_STACK_SIZE (2042)
|
||||
#define PCD_FILE_PATH "./DJI_cloud_data"
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
static int lastFrameCnt = 0;
|
||||
static std::queue<T_DjiLidarFrame *> lidarFrameQueue;
|
||||
static T_DjiMutexHandle queueMutex;
|
||||
static T_DjiSemaHandle dataSemaphore;
|
||||
static bool stopProcessing = false;
|
||||
static T_DjiSemaHandle taskExitSema;
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
static void DjiTest_PerceptionLidarCallback(uint8_t *recvBuffer, uint32_t bufferLen);
|
||||
static std::string DjiTest_getCurrentTimestamp();
|
||||
static void DjiTest_WriteLidarFrameToBinaryPcdFile(const T_DjiLidarFrame *frame);
|
||||
static void* DjiTest_ProcessLidarDataTask(void* arg);
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
void DjiUser_RunLidarDataSubscriptionSample(void) {
|
||||
int subscriptionDuration = 10;
|
||||
lastFrameCnt = 0;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
|
||||
osalHandler->MutexCreate(&queueMutex);
|
||||
osalHandler->SemaphoreCreate(0, &dataSemaphore);
|
||||
osalHandler->SemaphoreCreate(0, &taskExitSema);
|
||||
|
||||
std::cout << "Please ensure that there is enough storage space for the PCD files." << std::endl;
|
||||
|
||||
T_DjiTaskHandle processingThread;
|
||||
osalHandler->TaskCreate("LidarProcessingThread", DjiTest_ProcessLidarDataTask, USER_PERCEPTION_LIRDAR_TASK_STACK_SIZE, nullptr, &processingThread);
|
||||
|
||||
start:
|
||||
T_DjiReturnCode returnCode;
|
||||
returnCode = DjiPerception_Init();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
std::cout << "DjiPerception Init failed" << std::endl;
|
||||
return;
|
||||
}
|
||||
|
||||
std::cout << "start subscribe Lidar data from aircraft" << std::endl;
|
||||
|
||||
returnCode = DjiPerception_SubscribeLidarData(DjiTest_PerceptionLidarCallback);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
std::cout << "Request to subscribe Lidar data failed" << std::endl;
|
||||
goto subscribeFailed;
|
||||
}
|
||||
|
||||
osalHandler->TaskSleepMs(subscriptionDuration * 1000);
|
||||
|
||||
std::cout << "unsubscribe Lidar data " << std::endl;
|
||||
|
||||
subscribeFailed:
|
||||
returnCode = DjiPerception_UnsubscribeLidarData();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
std::cout << "Request to unsubscribe Lidar data failed" << std::endl;
|
||||
}
|
||||
|
||||
returnCode = DjiPerception_Deinit();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
std::cout << "DjiPerception DeInit failed" << std::endl;
|
||||
return;
|
||||
}
|
||||
|
||||
std::cout << "unsubscribe Lidar data success" << std::endl;
|
||||
|
||||
osalHandler->MutexLock(queueMutex);
|
||||
stopProcessing = true;
|
||||
osalHandler->MutexUnlock(queueMutex);
|
||||
|
||||
osalHandler->SemaphorePost(dataSemaphore);
|
||||
osalHandler->SemaphoreWait(taskExitSema);
|
||||
osalHandler->TaskDestroy(processingThread);
|
||||
osalHandler->MutexDestroy(queueMutex);
|
||||
osalHandler->SemaphoreDestroy(dataSemaphore);
|
||||
osalHandler->SemaphoreDestroy(taskExitSema);
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
static void DjiTest_PerceptionLidarCallback(uint8_t *LidarFrame, uint32_t bufferLen) {
|
||||
if (bufferLen != sizeof(T_DjiLidarFrame)) {
|
||||
std::cout << "usb recv Lidar length wrong, length = " << bufferLen << std::endl;
|
||||
return;
|
||||
}
|
||||
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
T_DjiLidarFrame * curFrame = (T_DjiLidarFrame *)osalHandler->Malloc(bufferLen);
|
||||
memcpy(curFrame, LidarFrame, bufferLen);
|
||||
|
||||
osalHandler->MutexLock(queueMutex);
|
||||
lidarFrameQueue.push(curFrame);
|
||||
osalHandler->MutexUnlock(queueMutex);
|
||||
|
||||
osalHandler->SemaphorePost(dataSemaphore);
|
||||
}
|
||||
std::string DjiTest_getCurrentTimestamp() {
|
||||
auto now = std::chrono::system_clock::now();
|
||||
|
||||
std::time_t nowTimeT = std::chrono::system_clock::to_time_t(now);
|
||||
|
||||
auto milliseconds = std::chrono::duration_cast<std::chrono::milliseconds>(now.time_since_epoch()) % 1000;
|
||||
|
||||
std::tm nowTm = *std::localtime(&nowTimeT);
|
||||
std::ostringstream oss;
|
||||
oss << std::put_time(&nowTm, "%Y%m%d_%H%M%S");
|
||||
oss << std::setfill('0') << std::setw(3) << milliseconds.count();
|
||||
|
||||
return oss.str();
|
||||
}
|
||||
|
||||
static void DjiTest_WriteLidarFrameToBinaryPcdFile(const T_DjiLidarFrame *frame) {
|
||||
uint32_t totalPoints = 0;
|
||||
size_t headerLen = 0;
|
||||
size_t pointDataSize = 0;
|
||||
size_t bufferSize = 0;
|
||||
char *buffer = NULL;
|
||||
size_t bufferPos = 0;
|
||||
int fd = 0;
|
||||
std::string directory = PCD_FILE_PATH;
|
||||
std::string filename = directory + "/DJI_cloud_data_" + DjiTest_getCurrentTimestamp() + ".pcd";
|
||||
char header[PCD_FILE_DEFAULT_LENGTH];
|
||||
|
||||
if (mkdir(directory.c_str(), 0755) != 0 && errno != EEXIST) {
|
||||
fprintf(stderr, "Error creating directory: %s\n", strerror(errno));
|
||||
return;
|
||||
}
|
||||
|
||||
for (uint16_t i = 0; i < frame->pkgNum; ++i) {
|
||||
totalPoints += frame->pkgs[i].header.dotNum;
|
||||
}
|
||||
|
||||
snprintf(header, sizeof(header),
|
||||
"# .PCD v0.7 - Point Cloud Data file format\n"
|
||||
"VERSION 0.7\n"
|
||||
"FIELDS x y z intensity label\n"
|
||||
"SIZE 4 4 4 1 1\n"
|
||||
"TYPE F F F U U\n"
|
||||
"COUNT 1 1 1 1 1\n"
|
||||
"WIDTH %u\n"
|
||||
"HEIGHT 1\n"
|
||||
"VIEWPOINT 0 0 0 1 0 0 0\n"
|
||||
"POINTS %u\n"
|
||||
"DATA binary\n",
|
||||
totalPoints, totalPoints);
|
||||
|
||||
// Calculate the size of the buffer needed
|
||||
headerLen = strlen(header);
|
||||
pointDataSize = totalPoints * (sizeof(float) * 3 + sizeof(uint8_t) * 2);
|
||||
bufferSize = headerLen + pointDataSize;
|
||||
|
||||
buffer = (char *)malloc(bufferSize);
|
||||
if (buffer == NULL) {
|
||||
fprintf(stderr, "Error allocating memory for buffer\n");
|
||||
return;
|
||||
}
|
||||
|
||||
memcpy(buffer + bufferPos, header, headerLen);
|
||||
bufferPos += headerLen;
|
||||
|
||||
for (uint16_t i = 0; i < frame->pkgNum; ++i) {
|
||||
const T_DjiPerceptionLidarDecodePkg *pkg = &frame->pkgs[i];
|
||||
for (uint16_t j = 0; j < pkg->header.dotNum; ++j) {
|
||||
const T_DJIPerceptionLidarPoint *point = &pkg->points[j];
|
||||
memcpy(buffer + bufferPos, &point->x, sizeof(float));
|
||||
bufferPos += sizeof(float);
|
||||
memcpy(buffer + bufferPos, &point->y, sizeof(float));
|
||||
bufferPos += sizeof(float);
|
||||
memcpy(buffer + bufferPos, &point->z, sizeof(float));
|
||||
bufferPos += sizeof(float);
|
||||
memcpy(buffer + bufferPos, &point->intensity, sizeof(uint8_t));
|
||||
bufferPos += sizeof(uint8_t);
|
||||
memcpy(buffer + bufferPos, &point->label, sizeof(uint8_t));
|
||||
bufferPos += sizeof(uint8_t);
|
||||
}
|
||||
}
|
||||
|
||||
fd = open(filename.c_str(), O_WRONLY | O_APPEND | O_CREAT, 0644);
|
||||
if (fd == -1) {
|
||||
fprintf(stderr, "Error opening file for writing\n");
|
||||
free(buffer);
|
||||
return;
|
||||
}
|
||||
|
||||
if (write(fd, buffer, bufferSize) == -1) {
|
||||
fprintf(stderr, "Error writing buffer to file\n");
|
||||
}
|
||||
|
||||
close(fd);
|
||||
free(buffer);
|
||||
}
|
||||
|
||||
static void* DjiTest_ProcessLidarDataTask(void* arg) {
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
|
||||
while(true) {
|
||||
osalHandler->SemaphoreWait(dataSemaphore);
|
||||
|
||||
osalHandler->MutexLock(queueMutex);
|
||||
bool shouldStop = stopProcessing && lidarFrameQueue.empty();
|
||||
if(shouldStop) {
|
||||
osalHandler->MutexUnlock(queueMutex);
|
||||
break;
|
||||
}
|
||||
|
||||
T_DjiLidarFrame *lidarFrame = lidarFrameQueue.front();
|
||||
lidarFrameQueue.pop();
|
||||
osalHandler->MutexUnlock(queueMutex);
|
||||
|
||||
DjiTest_WriteLidarFrameToBinaryPcdFile(lidarFrame);
|
||||
|
||||
int curFrameCnt = lidarFrame->frameCnt;
|
||||
std::cout << "Lidar data : curFrameCnt=" << curFrameCnt << std::endl;
|
||||
if(lastFrameCnt != 0 && (curFrameCnt - lastFrameCnt) > 1) {
|
||||
std::cout << "The number of lost packets during transmission is: " << curFrameCnt - lastFrameCnt - 1 << std::endl;
|
||||
}
|
||||
lastFrameCnt = curFrameCnt;
|
||||
|
||||
osalHandler->Free(lidarFrame);
|
||||
}
|
||||
|
||||
osalHandler->SemaphorePost(taskExitSema);
|
||||
return nullptr;
|
||||
}
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
@ -0,0 +1,49 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file test_lidar_entry.hpp
|
||||
* @brief This is the header file for "test_lidar_entry.cpp", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef TEST_LIDAR_ENTRY_H
|
||||
#define TEST_LIDAR_ENTRY_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_perception.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
void DjiUser_RunLidarDataSubscriptionSample(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // TEST_LIDAR_ENTRY_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
190
samples/sample_c++/module_sample/perception/test_radar_entry.cpp
Normal file
190
samples/sample_c++/module_sample/perception/test_radar_entry.cpp
Normal file
@ -0,0 +1,190 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file test_radar_entry.cpp
|
||||
* @brief
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "test_radar_entry.hpp"
|
||||
#include "dji_logger.h"
|
||||
#include <iostream>
|
||||
#include <ctime>
|
||||
#include <chrono>
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
static void DjiTest_PerceptionRadarCallback(E_DjiPerceptionRadarPosition radarPosition,
|
||||
uint8_t *radarDataBuffer, uint32_t bufferLen);
|
||||
static float parseVelocity(uint16_t velocity);
|
||||
static float parseBeamAngle(uint16_t beamAngle);
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
void DjiUser_RunRadarDataSubscriptionSample(void) {
|
||||
int subscriptionDuration = 10;
|
||||
T_DjiReturnCode returnCode;
|
||||
char inputChar;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
E_DjiPerceptionRadarPosition curPosition = MAX_RADAR_NUM;
|
||||
returnCode = DjiPerception_Init();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("DjiPerception Init failed");
|
||||
return;
|
||||
}
|
||||
|
||||
inputAgain:
|
||||
std::cout
|
||||
<< "| Available commands: |"
|
||||
<<
|
||||
std::endl;
|
||||
std::cout
|
||||
<< "| [d] Subscribe to downward millimeter wave radar data. |"
|
||||
<<
|
||||
std::endl;
|
||||
std::cout
|
||||
<< "| [u] Subscribe to upward millimeter wave radar data. |"
|
||||
<<
|
||||
std::endl;
|
||||
std::cout
|
||||
<< "| [f] Subscribe to forward millimeter wave radar data. |"
|
||||
<<
|
||||
std::endl;
|
||||
std::cout
|
||||
<< "| [b] Subscribe to backward millimeter wave radar data. |"
|
||||
<<
|
||||
std::endl;
|
||||
std::cout
|
||||
<< "| [l] Subscribe to leftward millimeter wave radar data. |"
|
||||
<<
|
||||
std::endl;
|
||||
std::cout
|
||||
<< "| [r] Subscribe to rightward millimeter wave radar data. |"
|
||||
<<
|
||||
std::endl;
|
||||
std::cout
|
||||
<< "| [q] quit |"
|
||||
<<
|
||||
std::endl;
|
||||
|
||||
std::cin >> inputChar;
|
||||
switch (inputChar) {
|
||||
case 'd':
|
||||
USER_LOG_INFO("Subscribe to downward millimeter wave radar data");
|
||||
curPosition = RADAR_POSITION_DOWN;
|
||||
break;
|
||||
case 'u':
|
||||
USER_LOG_INFO("Subscribe to upward millimeter wave radar data.");
|
||||
curPosition = RADAR_POSITION_UP;
|
||||
break;
|
||||
case 'f':
|
||||
USER_LOG_INFO("Subscribe to forward millimeter wave radar data.");
|
||||
curPosition = RADAR_POSITION_FRONT;
|
||||
break;
|
||||
case 'b':
|
||||
USER_LOG_INFO("Subscribe to backward millimeter wave radar data.");
|
||||
curPosition = RADAR_POSITION_BACK;
|
||||
break;
|
||||
case 'l':
|
||||
USER_LOG_INFO("Subscribe to leftward millimeter wave radar data.");
|
||||
curPosition = RADAR_POSITION_LEFT;
|
||||
break;
|
||||
case 'r':
|
||||
USER_LOG_INFO("Subscribe to rightward millimeter wave radar data.");
|
||||
curPosition = RADAR_POSITION_RIGHT;
|
||||
break;
|
||||
case 'q':
|
||||
goto endOfSample;
|
||||
default:
|
||||
goto inputAgain;
|
||||
}
|
||||
|
||||
returnCode = DjiPerception_SubscribeRadarData(curPosition, DjiTest_PerceptionRadarCallback);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Request to subscribe radar data failed");
|
||||
goto subscribeFailed;
|
||||
}
|
||||
|
||||
osalHandler->TaskSleepMs(subscriptionDuration * 1000);
|
||||
|
||||
subscribeFailed:
|
||||
|
||||
returnCode = DjiPerception_UnsubscribeRadarData(curPosition);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Request to unsubscribe Radar data failed");
|
||||
}
|
||||
goto inputAgain;
|
||||
|
||||
endOfSample:
|
||||
returnCode = DjiPerception_Deinit();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("DjiPerception DeInit failed");
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
static void DjiTest_PerceptionRadarCallback(E_DjiPerceptionRadarPosition radarPosition,
|
||||
uint8_t *radarDataBuffer, uint32_t bufferLen) {
|
||||
T_DjiRadarDataFrame* radarData;
|
||||
radarData = (T_DjiRadarDataFrame*)radarDataBuffer;
|
||||
|
||||
if (radarDataBuffer == nullptr || bufferLen == 0) {
|
||||
USER_LOG_ERROR("Invalid radar data: buffer=%p len=%u", radarDataBuffer, bufferLen);
|
||||
return;
|
||||
}
|
||||
|
||||
USER_LOG_INFO("RadarData[pos:%d][len:%u][units:%u][pack:%u/%u]",
|
||||
radarPosition,
|
||||
bufferLen,
|
||||
static_cast<unsigned>(radarData->headInfo.dataLen),
|
||||
static_cast<unsigned>(radarData->headInfo.curPack),
|
||||
static_cast<unsigned>(radarData->headInfo.packNum));
|
||||
|
||||
for (uint32_t i = 0; i < radarData->headInfo.dataLen; ++i) {
|
||||
const T_DjiRadarCloudUnit* unit = &radarData->data[i];
|
||||
float azimuth = unit->azimuth / 1000.0f - 2*3.14;
|
||||
float elevation = unit->elevation / 1000.0f - 2*3.14;
|
||||
float radius = unit->radius / 100.0f;
|
||||
float energy = unit->ene / 100.0f;
|
||||
float velocity = parseVelocity(unit->base_info.velocity);
|
||||
uint8_t snr = unit->base_info.snr;
|
||||
float beamAngle = parseBeamAngle(unit->base_info.beamAngle);
|
||||
|
||||
USER_LOG_INFO(
|
||||
"[Unit%d] Azimuth=%.3f(rad), Elevation=%.3f(rad), Radius=%.2f(m), Energy=%.2f, "
|
||||
"Velocity=%.2f(m/s), SNR=%u(dB), BeamAngle=%.2f(deg)",
|
||||
i, azimuth, elevation, radius, energy, velocity, snr, beamAngle);
|
||||
}
|
||||
}
|
||||
|
||||
static float parseVelocity(uint16_t velocity) {
|
||||
return (velocity - 32767) / 100.0f;
|
||||
}
|
||||
static float parseBeamAngle(uint16_t beamAngle) {
|
||||
if (beamAngle <= 450) {
|
||||
return beamAngle / 10.0f;
|
||||
} else {
|
||||
return (beamAngle / 10.0f) - 90.0f;
|
||||
}
|
||||
}
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
@ -0,0 +1,49 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file test_radar_entry.hpp
|
||||
* @brief This is the header file for "test_radar_entry.cpp", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef TEST_RADAR_ENTRY_H
|
||||
#define TEST_RADAR_ENTRY_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_perception.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
void DjiUser_RunRadarDataSubscriptionSample(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // TEST_RADAR_ENTRY_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
BIN
samples/sample_c++/module_sample/widget_manager/data/3K-5K.opus
Normal file
BIN
samples/sample_c++/module_sample/widget_manager/data/3K-5K.opus
Normal file
Binary file not shown.
@ -0,0 +1,461 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file test_widget_manager.cpp
|
||||
* @brief
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <iostream>
|
||||
#include "test_widget_manager.hpp"
|
||||
#include "dji_widget_manager.h"
|
||||
#include <dji_logger.h>
|
||||
#include <dji_platform.h>
|
||||
#include "unistd.h"
|
||||
#include "utils/util_misc.h"
|
||||
#include <fcntl.h>
|
||||
#include <sys/stat.h>
|
||||
#include <unistd.h>
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
T_DjiWidgetManagerFileList s_fileList;
|
||||
static FILE* s_widgetFileFd;
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
static void DjiTestWidgetManager_RecvWidgetStatesCallback(E_DjiMountPosition position, T_DjiWidgetStates *statesData, uint8_t widgetNum);
|
||||
static void DjiTestWidgetManager_RecvSpeakerStatesCallback(E_DjiMountPosition position, T_DjiSpeakerWidgetStates *speakerStates);
|
||||
static void DjiTestWidgetManager_RunSeachLightManagerSample(E_DjiMountPosition position);
|
||||
static void DjiTestWidgetManager_RunSpeakerManagerSample(E_DjiMountPosition position);
|
||||
static T_DjiReturnCode DjiWidgetManager_UsrDownloadCallback(T_DjiDownloadWidgetFileInfo packetInfo,
|
||||
const uint8_t *data,
|
||||
uint16_t dataLen);
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
T_DjiReturnCode DjiTest_WidgetMannagerStart(void)
|
||||
{
|
||||
T_DjiReturnCode djiStat;
|
||||
E_DjiMountPosition position;
|
||||
uint8_t index;
|
||||
uint32_t value;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
T_DjiWidgetStates state;
|
||||
int widget_type_input;
|
||||
int inputPosition = 0;
|
||||
int inputIndex = 0;
|
||||
bool continueFlag = true;
|
||||
int payloadType;
|
||||
T_DjiWidgetManagerFileList fileList;
|
||||
|
||||
std::cout << "Please select the position where the payload needs to be managed." << std::endl;
|
||||
std::cin >> inputPosition;
|
||||
std::cout << "Please select load type (1: third party payload; 2: DJI searchlight; 3: DJI speaker) ";
|
||||
std::cin >>payloadType;
|
||||
if (inputPosition < 1 || inputPosition > 8) {
|
||||
std::cerr << "Invalid input for position. Must be between 1 and 8." << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (payloadType < 1 || payloadType > 3) {
|
||||
std::cerr << "Invalid input for payload type. Must be between 1 and 3." << std::endl;
|
||||
return -1;
|
||||
}
|
||||
|
||||
position = static_cast<E_DjiMountPosition>(inputPosition);
|
||||
|
||||
djiStat = DjiWidgetManager_Init();
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test widget manager init error, stat = 0x%08llX", djiStat);
|
||||
return djiStat;
|
||||
}
|
||||
|
||||
djiStat = DjiWidgetManager_RegDownloadFileDataCallback(position, DjiWidgetManager_UsrDownloadCallback);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test regist download callback on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
goto finish_management;
|
||||
}
|
||||
|
||||
switch(payloadType){
|
||||
case 1:
|
||||
djiStat = DjiWidgetManager_WidgetDownloadFileList(position, &s_fileList);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test download payload widget file list on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
goto finish_management;
|
||||
}
|
||||
|
||||
for(int i = 0; i < s_fileList.totalCount; i++) {
|
||||
djiStat = DjiWidgetManager_DownloadFileByIndex(position, i);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test download payload widget by index on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
goto finish_management;
|
||||
}
|
||||
}
|
||||
|
||||
djiStat = DjiWidgetManager_SubscribePayloadWidgetStates(position, DjiTestWidgetManager_RecvWidgetStatesCallback);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test subscribe payload widget state on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
goto finish_management;
|
||||
}
|
||||
break;
|
||||
case 2:
|
||||
djiStat = DjiWidgetManager_WidgetDownloadFileList(position, &s_fileList);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test download payload widget file list on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
goto finish_management;
|
||||
}
|
||||
|
||||
for(int i = 0; i < s_fileList.totalCount; i++) {
|
||||
djiStat = DjiWidgetManager_DownloadFileByIndex(position, i);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test download payload widget by index on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
goto finish_management;
|
||||
}
|
||||
}
|
||||
|
||||
DjiTestWidgetManager_RunSeachLightManagerSample(position);
|
||||
goto finish_management;
|
||||
case 3:
|
||||
DjiTestWidgetManager_RunSpeakerManagerSample(position);
|
||||
goto finish_management;
|
||||
}
|
||||
|
||||
set_value:
|
||||
std::cout << "If you need to change the widget state, enter 1 " << std::endl;
|
||||
std::cin >> continueFlag;
|
||||
if(continueFlag != 1) goto finish_management;
|
||||
|
||||
std::cout << "Please enter the index and type to be set and the value to be set to :" << std::endl;
|
||||
std::cin >> inputIndex >> widget_type_input >> state.widgetValue;
|
||||
|
||||
if (widget_type_input >= 1 && widget_type_input <= 5)
|
||||
{
|
||||
state.widgetType = static_cast<E_DjiWidgetType>(widget_type_input);
|
||||
state.widgetIndex = inputIndex;
|
||||
}
|
||||
else
|
||||
{
|
||||
std::cout << "Invalid widget type input." << std::endl;
|
||||
goto finish_management;
|
||||
}
|
||||
|
||||
djiStat = DjiWidgetManager_SetWidgetState(position, state);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test set payload widget state on position: error, stat = 0x%08llX", position, djiStat);
|
||||
goto finish_management;
|
||||
}
|
||||
|
||||
goto set_value;
|
||||
|
||||
finish_management:
|
||||
djiStat = DjiWidgetManager_DeInit();
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test deinit widget manager error, stat = 0x%08llX", djiStat);
|
||||
return djiStat;
|
||||
}
|
||||
|
||||
if(s_fileList.fileListInfo != NULL) {
|
||||
free(s_fileList.fileListInfo);
|
||||
s_fileList.fileListInfo = NULL;
|
||||
}
|
||||
return djiStat;
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
static void DjiTestWidgetManager_RecvWidgetStatesCallback(E_DjiMountPosition position, T_DjiWidgetStates *statesData, uint8_t widgetNum)
|
||||
{
|
||||
printf("\033[32mrecv widget state form pos: %u\n", position);
|
||||
for (int i = 0; i < widgetNum; i++)
|
||||
{
|
||||
printf("widget index: %u type: %u value: %u\n",
|
||||
statesData[i].widgetIndex,
|
||||
static_cast<unsigned int>(statesData[i].widgetType),
|
||||
statesData[i].widgetValue);
|
||||
}
|
||||
printf("\033[0m");
|
||||
}
|
||||
|
||||
static void DjiTestWidgetManager_RecvSpeakerStatesCallback(E_DjiMountPosition position, T_DjiSpeakerWidgetStates *speakerStates) {
|
||||
printf("\033[0;34mrecv speaker state form pos: %u\n", position);
|
||||
printf("speaker playMode = %d\n", speakerStates->playMode);
|
||||
printf("speaker workMode = %d\n", speakerStates->workMode);
|
||||
printf("speaker playVloume = %u\n", speakerStates->playVloume);
|
||||
printf("speaker systemStates = %d\n", speakerStates->systemStates);
|
||||
printf("speaker playFileUuid = %s\n", speakerStates->playFileUuid);
|
||||
printf("speaker playFileName = %s\n", speakerStates->playFileName);
|
||||
printf("speaker playQuality = %u\n", speakerStates->playFileName);
|
||||
printf("speaker actualVolume = %u\n", speakerStates->actualVolume);
|
||||
printf("speaker limitVolumeOnTheGround = %u\n", speakerStates->limitVolumeOnTheGround);
|
||||
printf("\033[0m");
|
||||
}
|
||||
|
||||
void DjiTestWidgetManager_RunSeachLightManagerSample(E_DjiMountPosition position) {
|
||||
T_DjiReturnCode djiStat;
|
||||
T_DjiWidgetStates state;
|
||||
|
||||
djiStat = DjiWidgetManager_SubscribePayloadWidgetStates(position, DjiTestWidgetManager_RecvWidgetStatesCallback);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test subscribe search light widget state on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
// return ;
|
||||
}
|
||||
|
||||
std::cout<<"step 1: Turn on the searchlight."<<std::endl;
|
||||
state = {DJI_WIDGET_TYPE_SWITCH, 3, 1};
|
||||
djiStat = DjiWidgetManager_SetWidgetState(position, state);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test turn on search light widget on position :%d error, stat = 0x%08llX", position, djiStat);
|
||||
return ;
|
||||
}
|
||||
sleep(5);
|
||||
|
||||
std::cout<<"step 2: Setting the searchlight to burst mode"<<std::endl;
|
||||
state = {DJI_WIDGET_TYPE_SWITCH, 0, 1};
|
||||
djiStat = DjiWidgetManager_SetWidgetState(position, state);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test setting the searchlight to burst mode on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
return ;
|
||||
}
|
||||
sleep(5);
|
||||
|
||||
state = {DJI_WIDGET_TYPE_SWITCH, 0, 0};
|
||||
djiStat = DjiWidgetManager_SetWidgetState(position, state);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test setting up searchlight to roll out burst mode on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
return ;
|
||||
}
|
||||
sleep(5);
|
||||
|
||||
std::cout<<"step3: Switching the searchlight illumination mode"<<std::endl;
|
||||
state = {DJI_WIDGET_TYPE_LIST, 0, 0};
|
||||
djiStat = DjiWidgetManager_SetWidgetState(position, state);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test switching the searchlight illumination mode on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
return ;
|
||||
}
|
||||
sleep(5);
|
||||
|
||||
state = {DJI_WIDGET_TYPE_SWITCH, 2, 1};
|
||||
djiStat = DjiWidgetManager_SetWidgetState(position, state);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test turn off the searchlight on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
return ;
|
||||
}
|
||||
sleep(5);
|
||||
|
||||
state = {DJI_WIDGET_TYPE_SWITCH, 2, 2};
|
||||
djiStat = DjiWidgetManager_SetWidgetState(position, state);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test turn off the searchlight on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
return ;
|
||||
}
|
||||
sleep(5);
|
||||
|
||||
std::cout<<"step4: Turn off the searchlight."<<std::endl;
|
||||
state = {DJI_WIDGET_TYPE_SWITCH, 3, 0};
|
||||
djiStat = DjiWidgetManager_SetWidgetState(position, state);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test turn off the searchlight on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
return ;
|
||||
}
|
||||
|
||||
djiStat = DjiWidgetManager_UnsubscribePayloadWidgetStates(position);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test unsubscribe search light widget state on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
// return ;
|
||||
}
|
||||
}
|
||||
|
||||
static void DjiTestWidgetManager_RunSpeakerManagerSample(E_DjiMountPosition position) {
|
||||
T_DjiReturnCode djiStat;
|
||||
T_DjiSpeakerWidgetStatesParam param;
|
||||
T_DjiSpeakerAudioFileInfo audioFileInfo;
|
||||
char curFileDirPath[WIDGET_MANAGER_MAX_FILE_PATH_LEN];
|
||||
char filePath[WIDGET_MANAGER_MAX_FILE_PATH_LEN];
|
||||
|
||||
djiStat = DjiUserUtil_GetCurrentFileDirPath(__FILE__, WIDGET_MANAGER_MAX_FILE_PATH_LEN, curFileDirPath);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Get file current path error, stat = 0x%08llX", djiStat);
|
||||
return ;
|
||||
}
|
||||
snprintf(filePath, WIDGET_MANAGER_MAX_FILE_PATH_LEN, "%sdata/3K-5K.opus", curFileDirPath);
|
||||
const char* fileName = "3K-5K.opus";
|
||||
const char* uuid = "abcdef";
|
||||
|
||||
memset(&audioFileInfo, 0, sizeof(audioFileInfo));
|
||||
audioFileInfo.fileType = DJI_SPEAKER_WIDGET_FILE_TYPE_OPUS;
|
||||
memcpy(audioFileInfo.fileName, fileName, strlen(fileName));
|
||||
memcpy(audioFileInfo.filePath, filePath, strlen(filePath));
|
||||
memcpy(audioFileInfo.uuid, uuid, strlen(uuid));
|
||||
audioFileInfo.fileBitrate = DJI_SPEAKER_WIDGET_AUDIO_DECODE_BITRATE_32000;
|
||||
|
||||
std::cout<<"step 1: subscribe widget state of speaker"<<std::endl;
|
||||
djiStat = DjiWidgetManager_SubscribeSpeakerStates(position, DjiTestWidgetManager_RecvSpeakerStatesCallback);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test subscribe speaker widget state on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
// return ;
|
||||
}
|
||||
|
||||
std::cout<<"step 2: set playing param of speaker"<<std::endl;
|
||||
param = {DJI_WIDGET_MGR_SPEAKER_PARAM_VOLUME, 20};
|
||||
djiStat = DjiWidgetManager_SetSpeakertState(position, ¶m);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test setting the speaker volume on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
return ;
|
||||
}
|
||||
|
||||
param = {DJI_WIDGET_MGR_SPEAKER_PARAM_PLAY_MODE, 1};
|
||||
djiStat = DjiWidgetManager_SetSpeakertState(position, ¶m);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test set the speaker play mode on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
return ;
|
||||
}
|
||||
|
||||
std::cout<<"step 3: send audio file data to speaker"<<std::endl;
|
||||
djiStat = DjiWidgetManager_SendSpeakerAudioData(position, &audioFileInfo);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test send audio file to speaker on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
return ;
|
||||
}
|
||||
|
||||
|
||||
std::cout<<"step 4: play the audio file"<<std::endl;
|
||||
param = {DJI_WIDGET_MGR_SPEAKER_PARAM_PALY_ACTION, 0};
|
||||
djiStat = DjiWidgetManager_SetSpeakertState(position, ¶m);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test set the speaker to start play on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
return ;
|
||||
}
|
||||
|
||||
sleep(10);
|
||||
|
||||
param = {DJI_WIDGET_MGR_SPEAKER_PARAM_PALY_ACTION, 1};
|
||||
djiStat = DjiWidgetManager_SetSpeakertState(position, ¶m);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test set the speaker to stop play on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
return ;
|
||||
}
|
||||
|
||||
std::cout<<"step 5: stop subscribe speaker state"<<std::endl;
|
||||
djiStat = DjiWidgetManager_UnsubscribeSpeakerStates(position);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
|
||||
{
|
||||
USER_LOG_ERROR("Dji test unsubscribe speaker widget state on position:%d error, stat = 0x%08llX", position, djiStat);
|
||||
// return ;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiWidgetManager_UsrDownloadCallback(T_DjiDownloadWidgetFileInfo packetInfo,
|
||||
const uint8_t *data,
|
||||
uint16_t dataLen) {
|
||||
std::string directory;
|
||||
std::string fileName = s_fileList.fileListInfo[packetInfo.fileIndex].fileName;
|
||||
std::string path;
|
||||
directory = "widget_file_from_position_" + std::to_string(packetInfo.position) ;
|
||||
path = directory + '/' + fileName;
|
||||
size_t realLen;
|
||||
|
||||
if (mkdir(directory.c_str(), 0755) != 0 && errno != EEXIST) {
|
||||
USER_LOG_ERROR("Error creating directory: %s\n", strerror(errno));
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
switch (packetInfo.downloadFileEvent) {
|
||||
case DJI_DOWNLOAD_FILE_EVENT_START: {
|
||||
s_widgetFileFd = fopen(path.c_str(), "wb+");
|
||||
if(s_widgetFileFd == NULL) {
|
||||
USER_LOG_ERROR("Dji test Open widget file failed");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
realLen = fwrite(data, 1, dataLen, s_widgetFileFd);
|
||||
if(realLen != dataLen) {
|
||||
USER_LOG_ERROR("Dji test write widget data failed");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case DJI_DOWNLOAD_FILE_EVENT_TRANSFER: {
|
||||
if(s_widgetFileFd != NULL) {
|
||||
realLen = fwrite(data, 1, dataLen, s_widgetFileFd);
|
||||
if(realLen != dataLen) {
|
||||
USER_LOG_ERROR("Dji test write widget data failed");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
case DJI_DOWNLOAD_FILE_EVENT_END: {
|
||||
if(s_widgetFileFd != NULL) {
|
||||
realLen = fwrite(data, 1, dataLen, s_widgetFileFd);
|
||||
if(realLen != dataLen) {
|
||||
USER_LOG_ERROR("Dji test write widget data failed");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
}
|
||||
fclose(s_widgetFileFd);
|
||||
s_widgetFileFd = NULL;
|
||||
break;
|
||||
}
|
||||
case DJI_DOWNLOAD_FILE_EVENT_START_TRANSFER_END: {
|
||||
s_widgetFileFd = fopen(path.c_str(), "wb+");
|
||||
if(s_widgetFileFd == NULL) {
|
||||
USER_LOG_ERROR("Dji test Open widget file failed");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
realLen = fwrite(data, 1, dataLen, s_widgetFileFd);
|
||||
if(realLen != dataLen) {
|
||||
USER_LOG_ERROR("Dji test write widget data failed");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
fclose(s_widgetFileFd);
|
||||
s_widgetFileFd = NULL;
|
||||
break;
|
||||
}
|
||||
default: {
|
||||
USER_LOG_ERROR("Dji test unknown download event");
|
||||
break;
|
||||
}
|
||||
}
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
@ -0,0 +1,51 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file test_widget_manager.hpp
|
||||
* @brief This is the header file for "test_widget_manager.cpp", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef DJI_WIDGET_MANAGER_INTERNAL_H
|
||||
#define DJI_WIDGET_MANAGER_INTERNAL_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_typedef.h"
|
||||
// #include "dji_widget_manager.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
T_DjiReturnCode DjiTest_WidgetMannagerStart(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // DJI_WIDGET_MANAGER_INTERNAL_H
|
||||
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
@ -48,15 +48,10 @@ T_DjiReturnCode Osal_FileOpen(const char *fileName, const char *fileMode, T_DjiF
|
||||
|
||||
*fileObj = fopen(fileName, fileMode);
|
||||
if (*fileObj == NULL) {
|
||||
goto out;
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
|
||||
out:
|
||||
free(*fileObj);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
T_DjiReturnCode Osal_FileClose(T_DjiFileHandle fileObj)
|
||||
|
||||
@ -32,6 +32,7 @@
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define SOCKET_RECV_BUF_MAX_SIZE (1000 * 1000 * 10)
|
||||
#define MAX_UDP_PAYLOAD_SIZE 65507
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
typedef struct {
|
||||
@ -141,6 +142,7 @@ T_DjiReturnCode Osal_UdpSendData(T_DjiSocketHandle socketHandle, const char *ipA
|
||||
struct sockaddr_in addr;
|
||||
T_SocketHandleStruct *socketHandleStruct = (T_SocketHandleStruct *) socketHandle;
|
||||
int32_t ret;
|
||||
ssize_t total_sent = 0;
|
||||
|
||||
if (socketHandle <= 0 || ipAddr == NULL || port == 0 || buf == NULL || len == 0 || realLen == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
@ -151,13 +153,21 @@ T_DjiReturnCode Osal_UdpSendData(T_DjiSocketHandle socketHandle, const char *ipA
|
||||
addr.sin_port = htons(port);
|
||||
addr.sin_addr.s_addr = inet_addr(ipAddr);
|
||||
|
||||
ret = sendto(socketHandleStruct->socketFd, buf, len, 0, (struct sockaddr *) &addr, sizeof(struct sockaddr_in));
|
||||
if (ret >= 0) {
|
||||
*realLen = ret;
|
||||
} else {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
while (len > 0) {
|
||||
size_t chunk_size = (len > MAX_UDP_PAYLOAD_SIZE) ? MAX_UDP_PAYLOAD_SIZE : len;
|
||||
ssize_t sent = sendto(socketHandleStruct->socketFd, buf, chunk_size, 0, (struct sockaddr *) &addr, sizeof(struct sockaddr_in));
|
||||
|
||||
if (sent < 0) {
|
||||
perror("sendto failed");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
buf += sent;
|
||||
len -= sent;
|
||||
total_sent += sent;
|
||||
}
|
||||
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
|
||||
@ -138,3 +138,5 @@ if (OpenCV_FOUND)
|
||||
target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS})
|
||||
endif ()
|
||||
|
||||
target_link_libraries(${PROJECT_NAME} dl)
|
||||
|
||||
|
||||
@ -25,6 +25,8 @@
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <liveview/test_liveview_entry.hpp>
|
||||
#include <perception/test_perception_entry.hpp>
|
||||
#include <perception/test_lidar_entry.hpp>
|
||||
#include <perception/test_radar_entry.hpp>
|
||||
#include <flight_control/test_flight_control.h>
|
||||
#include <gimbal/test_gimbal_entry.hpp>
|
||||
#include "application.hpp"
|
||||
@ -71,6 +73,8 @@ start:
|
||||
<< "| [d] Stereo vision view sample - display the stereo image |\n"
|
||||
<< "| [e] Run camera manager sample - you can test camera's functions interactively |\n"
|
||||
<< "| [f] Start rtk positioning sample - you can receive rtk rtcm data when rtk signal is ok |\n"
|
||||
<< "| [g] Request Lidar data sample - Request Lidar data and store the point cloud data as pcd files |\n"
|
||||
<< "| [h] Request Radar data sample - Request radar data |\n"
|
||||
<< std::endl;
|
||||
|
||||
std::cin >> inputChar;
|
||||
@ -105,6 +109,12 @@ start:
|
||||
|
||||
USER_LOG_INFO("Start rtk positioning sample successfully");
|
||||
break;
|
||||
case 'g':
|
||||
DjiUser_RunLidarDataSubscriptionSample();
|
||||
break;
|
||||
case 'h':
|
||||
DjiUser_RunRadarDataSubscriptionSample();
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
88
samples/sample_c++/platform/linux/manifold3/CMakeLists.txt
Normal file
88
samples/sample_c++/platform/linux/manifold3/CMakeLists.txt
Normal file
@ -0,0 +1,88 @@
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
project(dji_sdk_demo_on_manifold3_cxx LANGUAGES CXX C)
|
||||
|
||||
set(CMAKE_C_COMPILER "aarch64-linux-gnu-gcc" CACHE STRING "C compiler")
|
||||
set(CMAKE_CXX_COMPILER "aarch64-linux-gnu-g++" CACHE STRING "C++ compiler")
|
||||
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -pthread -std=gnu99")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -pthread")
|
||||
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -pthread")
|
||||
|
||||
add_compile_definitions(
|
||||
_GNU_SOURCE
|
||||
PLATFORM_ARCH_AARCH64=1
|
||||
SYSTEM_ARCH_LINUX=1
|
||||
)
|
||||
|
||||
include_directories(
|
||||
../../../module_sample
|
||||
../../../../sample_c/module_sample
|
||||
../common
|
||||
../manifold3/application
|
||||
include_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/include)
|
||||
)
|
||||
|
||||
file(GLOB_RECURSE MODULE_SAMPLE_SRC
|
||||
../../../module_sample/liveview/*.c*
|
||||
../../../module_sample/camera_manager/*.c*
|
||||
../../../module_sample/hms_manager/*.c*
|
||||
../../../module_sample/perception/*.c*
|
||||
../../../module_sample/gimbal/*.c*
|
||||
../../../module_sample/flight_controller/*.c*
|
||||
../../../module_sample/hms_manager/*.c*
|
||||
../../../module_sample/widget_manager/*.c*
|
||||
../../../../sample_c/module_sample/*.c
|
||||
../../../../sample_c/module_sample/widget_interaction_test/*.c
|
||||
)
|
||||
file(GLOB_RECURSE MODULE_COMMON_SRC ../common/*.c*)
|
||||
file(GLOB_RECURSE MODULE_HAL_SRC hal/*.c*)
|
||||
file(GLOB_RECURSE MODULE_APP_SRC application/*.c*)
|
||||
|
||||
set(TOOLCHAIN_NAME aarch64-linux-gnu-gcc)
|
||||
link_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/lib/${TOOLCHAIN_NAME})
|
||||
|
||||
add_executable(${PROJECT_NAME}
|
||||
${MODULE_APP_SRC}
|
||||
${MODULE_SAMPLE_SRC}
|
||||
${MODULE_COMMON_SRC}
|
||||
${MODULE_HAL_SRC}
|
||||
)
|
||||
|
||||
target_link_libraries(${PROJECT_NAME}
|
||||
PRIVATE
|
||||
${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/lib/${TOOLCHAIN_NAME}/libpayloadsdk.a
|
||||
stdc++
|
||||
m
|
||||
dl
|
||||
)
|
||||
|
||||
# OpenCV
|
||||
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)
|
||||
target_include_directories(${PROJECT_NAME} PRIVATE ${OpenCV_INCLUDE_DIRS})
|
||||
target_link_libraries(${PROJECT_NAME} PRIVATE ${OpenCV_LIBRARIES})
|
||||
else ()
|
||||
message(STATUS "Did not find OpenCV in the system, image data is inside RecvContainer as raw data")
|
||||
endif ()
|
||||
|
||||
# FFMPEG
|
||||
find_package(PkgConfig)
|
||||
pkg_check_modules(FFMPEG REQUIRED libavcodec libavformat libavutil libswscale)
|
||||
if (FFMPEG_FOUND)
|
||||
message(STATUS "Found FFMPEG installed in the system")
|
||||
message(STATUS " - Includes: ${FFMPEG_INCLUDE_DIRS}")
|
||||
message(STATUS " - Libraries: ${FFMPEG_LIBRARIES}")
|
||||
|
||||
target_link_libraries(${PROJECT_NAME} PRIVATE ${FFMPEG_LIBRARIES})
|
||||
target_include_directories(${PROJECT_NAME} PRIVATE ${FFMPEG_INCLUDE_DIRS})
|
||||
target_compile_definitions(${PROJECT_NAME} PRIVATE FFMPEG_INSTALLED)
|
||||
else()
|
||||
message(STATUS "Cannot Find FFMPEG")
|
||||
endif()
|
||||
|
||||
set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
|
||||
@ -0,0 +1,404 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file application.cpp
|
||||
* @brief
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "application.hpp"
|
||||
#include "dji_sdk_app_info.h"
|
||||
#include <dji_platform.h>
|
||||
#include <dji_logger.h>
|
||||
#include <dji_core.h>
|
||||
#include <dji_aircraft_info.h>
|
||||
#include <csignal>
|
||||
#include "dji_sdk_config.h"
|
||||
|
||||
#include "../common/osal/osal.h"
|
||||
#include "../common/osal/osal_fs.h"
|
||||
#include "../common/osal/osal_socket.h"
|
||||
#include "../hal/hal_usb_bulk.h"
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define DJI_LOG_PATH "logs/DJI"
|
||||
#define DJI_LOG_INDEX_FILE_NAME "logs/index"
|
||||
#define DJI_LOG_FOLDER_NAME "logs"
|
||||
#define DJI_LOG_PATH_MAX_SIZE (128)
|
||||
#define DJI_LOG_FOLDER_NAME_MAX_SIZE (32)
|
||||
#define DJI_SYSTEM_CMD_STR_MAX_SIZE (64)
|
||||
#define DJI_LOG_MAX_COUNT (10)
|
||||
|
||||
#define USER_UTIL_UNUSED(x) ((x) = (x))
|
||||
#define USER_UTIL_MIN(a, b) (((a) < (b)) ? (a) : (b))
|
||||
#define USER_UTIL_MAX(a, b) (((a) > (b)) ? (a) : (b))
|
||||
|
||||
extern "C" {
|
||||
T_DjiReturnCode DjiTest_WidgetStartService(void);
|
||||
}
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
static FILE *s_djiLogFile;
|
||||
static FILE *s_djiLogFileCnt;
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
static void DjiUser_NormalExitHandler(int signalNum);
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
Application::Application(int argc, char **argv)
|
||||
{
|
||||
Application::DjiUser_SetupEnvironment();
|
||||
Application::DjiUser_ApplicationStart();
|
||||
|
||||
Osal_TaskSleepMs(3000);
|
||||
}
|
||||
|
||||
Application::~Application()
|
||||
= default;
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
void Application::DjiUser_SetupEnvironment()
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiOsalHandler osalHandler = {0};
|
||||
T_DjiHalUsbBulkHandler usbBulkHandler = {0};
|
||||
T_DjiLoggerConsole printConsole;
|
||||
T_DjiLoggerConsole localRecordConsole;
|
||||
T_DjiFileSystemHandler fileSystemHandler = {0};
|
||||
T_DjiSocketHandler socketHandler = {0};
|
||||
T_DjiHalNetworkHandler networkHandler = {0};
|
||||
|
||||
socketHandler.Socket = Osal_Socket;
|
||||
socketHandler.Bind = Osal_Bind;
|
||||
socketHandler.Close = Osal_Close;
|
||||
socketHandler.UdpSendData = Osal_UdpSendData;
|
||||
socketHandler.UdpRecvData = Osal_UdpRecvData;
|
||||
socketHandler.TcpListen = Osal_TcpListen;
|
||||
socketHandler.TcpAccept = Osal_TcpAccept;
|
||||
socketHandler.TcpConnect = Osal_TcpConnect;
|
||||
socketHandler.TcpSendData = Osal_TcpSendData;
|
||||
socketHandler.TcpRecvData = Osal_TcpRecvData;
|
||||
|
||||
osalHandler.TaskCreate = Osal_TaskCreate;
|
||||
osalHandler.TaskDestroy = Osal_TaskDestroy;
|
||||
osalHandler.TaskSleepMs = Osal_TaskSleepMs;
|
||||
osalHandler.MutexCreate = Osal_MutexCreate;
|
||||
osalHandler.MutexDestroy = Osal_MutexDestroy;
|
||||
osalHandler.MutexLock = Osal_MutexLock;
|
||||
osalHandler.MutexUnlock = Osal_MutexUnlock;
|
||||
osalHandler.SemaphoreCreate = Osal_SemaphoreCreate;
|
||||
osalHandler.SemaphoreDestroy = Osal_SemaphoreDestroy;
|
||||
osalHandler.SemaphoreWait = Osal_SemaphoreWait;
|
||||
osalHandler.SemaphoreTimedWait = Osal_SemaphoreTimedWait;
|
||||
osalHandler.SemaphorePost = Osal_SemaphorePost;
|
||||
osalHandler.Malloc = Osal_Malloc;
|
||||
osalHandler.Free = Osal_Free;
|
||||
osalHandler.GetTimeMs = Osal_GetTimeMs;
|
||||
osalHandler.GetTimeUs = Osal_GetTimeUs;
|
||||
osalHandler.GetRandomNum = Osal_GetRandomNum,
|
||||
|
||||
printConsole.func = DjiUser_PrintConsole;
|
||||
printConsole.consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO;
|
||||
printConsole.isSupportColor = true;
|
||||
|
||||
localRecordConsole.consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_DEBUG;
|
||||
localRecordConsole.func = DjiUser_LocalWrite;
|
||||
localRecordConsole.isSupportColor = false;
|
||||
|
||||
usbBulkHandler.UsbBulkInit = HalUsbBulk_Init;
|
||||
usbBulkHandler.UsbBulkDeInit = HalUsbBulk_DeInit;
|
||||
usbBulkHandler.UsbBulkWriteData = HalUsbBulk_WriteData;
|
||||
usbBulkHandler.UsbBulkReadData = HalUsbBulk_ReadData;
|
||||
usbBulkHandler.UsbBulkGetDeviceInfo = HalUsbBulk_GetDeviceInfo;
|
||||
|
||||
fileSystemHandler.FileOpen = Osal_FileOpen,
|
||||
fileSystemHandler.FileClose = Osal_FileClose,
|
||||
fileSystemHandler.FileWrite = Osal_FileWrite,
|
||||
fileSystemHandler.FileRead = Osal_FileRead,
|
||||
fileSystemHandler.FileSync = Osal_FileSync,
|
||||
fileSystemHandler.FileSeek = Osal_FileSeek,
|
||||
fileSystemHandler.DirOpen = Osal_DirOpen,
|
||||
fileSystemHandler.DirClose = Osal_DirClose,
|
||||
fileSystemHandler.DirRead = Osal_DirRead,
|
||||
fileSystemHandler.Mkdir = Osal_Mkdir,
|
||||
fileSystemHandler.Unlink = Osal_Unlink,
|
||||
fileSystemHandler.Rename = Osal_Rename,
|
||||
fileSystemHandler.Stat = Osal_Stat,
|
||||
|
||||
returnCode = DjiPlatform_RegOsalHandler(&osalHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Register osal handler error.");
|
||||
}
|
||||
|
||||
returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Register hal network handler error");
|
||||
}
|
||||
|
||||
returnCode = DjiPlatform_RegSocketHandler(&socketHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("register osal socket handler error");
|
||||
}
|
||||
|
||||
returnCode = DjiPlatform_RegFileSystemHandler(&fileSystemHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Register osal filesystem handler error.");
|
||||
}
|
||||
|
||||
if (DjiUser_LocalWriteFsInit(DJI_LOG_PATH) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("File system init error.");
|
||||
}
|
||||
|
||||
returnCode = DjiLogger_AddConsole(&printConsole);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Add printf console error.");
|
||||
}
|
||||
|
||||
returnCode = DjiLogger_AddConsole(&localRecordConsole);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Add printf console error.");
|
||||
}
|
||||
}
|
||||
|
||||
void Application::DjiUser_ApplicationStart()
|
||||
{
|
||||
T_DjiUserInfo userInfo;
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo;
|
||||
T_DjiFirmwareVersion firmwareVersion = {
|
||||
.majorVersion = 1,
|
||||
.minorVersion = 0,
|
||||
.modifyVersion = 0,
|
||||
.debugVersion = 1,
|
||||
};
|
||||
|
||||
// attention: when the program is hand up ctrl-c will generate the coredump file
|
||||
signal(SIGTERM, DjiUser_NormalExitHandler);
|
||||
|
||||
returnCode = DjiUser_FillInUserInfo(&userInfo);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Fill user info error, please check user info config.");
|
||||
}
|
||||
|
||||
returnCode = DjiCore_Init(&userInfo);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Core init error.");
|
||||
}
|
||||
|
||||
returnCode = DjiAircraftInfo_GetBaseInfo(&aircraftInfoBaseInfo);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Get aircraft base info error.");
|
||||
}
|
||||
|
||||
if (aircraftInfoBaseInfo.mountPosition != DJI_MOUNT_POSITION_EXTENSION_PORT &&
|
||||
aircraftInfoBaseInfo.djiAdapterType != DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE &&
|
||||
aircraftInfoBaseInfo.mountPositionType != DJI_MOUNT_POSITION_TYPE_MANIFOLD3_ONBOARD &&
|
||||
aircraftInfoBaseInfo.djiAdapterType != DJI_SDK_ADAPTER_TYPE_SKYPORT_V3) {
|
||||
throw std::runtime_error("Please run this sample on extension port or skyport v3.");
|
||||
}
|
||||
|
||||
returnCode = DjiCore_SetAlias("PSDK_APPALIAS");
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Set alias error.");
|
||||
}
|
||||
|
||||
returnCode = DjiCore_SetFirmwareVersion(firmwareVersion);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Set firmware version error.");
|
||||
}
|
||||
|
||||
returnCode = DjiCore_SetSerialNumber("PSDK12345678XX");
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Set serial number error");
|
||||
}
|
||||
|
||||
returnCode = DjiTest_WidgetStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("widget sample init error");
|
||||
}
|
||||
|
||||
returnCode = DjiCore_ApplicationStart();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Start sdk application error.");
|
||||
}
|
||||
|
||||
USER_LOG_INFO("Application start.");
|
||||
}
|
||||
|
||||
T_DjiReturnCode Application::DjiUser_PrintConsole(const uint8_t *data, uint16_t dataLen)
|
||||
{
|
||||
printf("%s", data);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode Application::DjiUser_LocalWrite(const uint8_t *data, uint16_t dataLen)
|
||||
{
|
||||
int32_t realLen;
|
||||
|
||||
if (s_djiLogFile == nullptr) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
}
|
||||
|
||||
realLen = fwrite(data, 1, dataLen, s_djiLogFile);
|
||||
fflush(s_djiLogFile);
|
||||
if (realLen == dataLen) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
} else {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
}
|
||||
}
|
||||
|
||||
T_DjiReturnCode Application::DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo)
|
||||
{
|
||||
memset(userInfo->appName, 0, sizeof(userInfo->appName));
|
||||
memset(userInfo->appId, 0, sizeof(userInfo->appId));
|
||||
memset(userInfo->appKey, 0, sizeof(userInfo->appKey));
|
||||
memset(userInfo->appLicense, 0, sizeof(userInfo->appLicense));
|
||||
memset(userInfo->developerAccount, 0, sizeof(userInfo->developerAccount));
|
||||
memset(userInfo->baudRate, 0, sizeof(userInfo->baudRate));
|
||||
|
||||
if (strlen(USER_APP_NAME) >= sizeof(userInfo->appName) ||
|
||||
strlen(USER_APP_ID) > sizeof(userInfo->appId) ||
|
||||
strlen(USER_APP_KEY) > sizeof(userInfo->appKey) ||
|
||||
strlen(USER_APP_LICENSE) > sizeof(userInfo->appLicense) ||
|
||||
strlen(USER_DEVELOPER_ACCOUNT) >= sizeof(userInfo->developerAccount) ||
|
||||
strlen(USER_BAUD_RATE) > sizeof(userInfo->baudRate)) {
|
||||
USER_LOG_ERROR("Length of user information string is beyond limit. Please check.");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
if (!strcmp(USER_APP_NAME, "your_app_name") ||
|
||||
!strcmp(USER_APP_ID, "your_app_id") ||
|
||||
!strcmp(USER_APP_KEY, "your_app_key") ||
|
||||
!strcmp(USER_BAUD_RATE, "your_app_license") ||
|
||||
!strcmp(USER_DEVELOPER_ACCOUNT, "your_developer_account") ||
|
||||
!strcmp(USER_BAUD_RATE, "your_baud_rate")) {
|
||||
USER_LOG_ERROR(
|
||||
"Please fill in correct user information to 'samples/sample_c++/platform/linux/nvidia_jetson/application/dji_sdk_app_info.h' file.");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
strncpy(userInfo->appName, USER_APP_NAME, sizeof(userInfo->appName) - 1);
|
||||
memcpy(userInfo->appId, USER_APP_ID, USER_UTIL_MIN(sizeof(userInfo->appId), strlen(USER_APP_ID)));
|
||||
memcpy(userInfo->appKey, USER_APP_KEY, USER_UTIL_MIN(sizeof(userInfo->appKey), strlen(USER_APP_KEY)));
|
||||
memcpy(userInfo->appLicense, USER_APP_LICENSE,
|
||||
USER_UTIL_MIN(sizeof(userInfo->appLicense), strlen(USER_APP_LICENSE)));
|
||||
memcpy(userInfo->baudRate, USER_BAUD_RATE, USER_UTIL_MIN(sizeof(userInfo->baudRate), strlen(USER_BAUD_RATE)));
|
||||
strncpy(userInfo->developerAccount, USER_DEVELOPER_ACCOUNT, sizeof(userInfo->developerAccount) - 1);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode Application::DjiUser_LocalWriteFsInit(const char *path)
|
||||
{
|
||||
T_DjiReturnCode djiReturnCode = DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
char filePath[DJI_LOG_PATH_MAX_SIZE];
|
||||
char systemCmd[DJI_SYSTEM_CMD_STR_MAX_SIZE];
|
||||
char folderName[DJI_LOG_FOLDER_NAME_MAX_SIZE];
|
||||
time_t currentTime = time(nullptr);
|
||||
struct tm *localTime = localtime(¤tTime);
|
||||
uint16_t logFileIndex = 0;
|
||||
uint16_t currentLogFileIndex;
|
||||
uint8_t ret;
|
||||
|
||||
if (localTime == nullptr) {
|
||||
printf("Get local time error.\r\n");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
if (access(DJI_LOG_FOLDER_NAME, F_OK) != 0) {
|
||||
sprintf(folderName, "mkdir %s", DJI_LOG_FOLDER_NAME);
|
||||
ret = system(folderName);
|
||||
if (ret != 0) {
|
||||
printf("Create new log folder error, ret:%d.\r\n", ret);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
}
|
||||
|
||||
s_djiLogFileCnt = fopen(DJI_LOG_INDEX_FILE_NAME, "rb+");
|
||||
if (s_djiLogFileCnt == nullptr) {
|
||||
s_djiLogFileCnt = fopen(DJI_LOG_INDEX_FILE_NAME, "wb+");
|
||||
if (s_djiLogFileCnt == nullptr) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
} else {
|
||||
ret = fseek(s_djiLogFileCnt, 0, SEEK_SET);
|
||||
if (ret != 0) {
|
||||
printf("Seek log count file error, ret: %d, errno: %d.\r\n", ret, errno);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
ret = fread((uint16_t * ) & logFileIndex, 1, sizeof(uint16_t), s_djiLogFileCnt);
|
||||
if (ret != sizeof(uint16_t)) {
|
||||
printf("Read log file index error.\r\n");
|
||||
}
|
||||
}
|
||||
|
||||
currentLogFileIndex = logFileIndex;
|
||||
logFileIndex++;
|
||||
|
||||
ret = fseek(s_djiLogFileCnt, 0, SEEK_SET);
|
||||
if (ret != 0) {
|
||||
printf("Seek log file error, ret: %d, errno: %d.\r\n", ret, errno);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
ret = fwrite((uint16_t * ) & logFileIndex, 1, sizeof(uint16_t), s_djiLogFileCnt);
|
||||
if (ret != sizeof(uint16_t)) {
|
||||
printf("Write log file index error.\r\n");
|
||||
fclose(s_djiLogFileCnt);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
fclose(s_djiLogFileCnt);
|
||||
|
||||
sprintf(filePath, "%s_%04d_%04d%02d%02d_%02d-%02d-%02d.log", path, currentLogFileIndex,
|
||||
localTime->tm_year + 1900, localTime->tm_mon + 1, localTime->tm_mday,
|
||||
localTime->tm_hour, localTime->tm_min, localTime->tm_sec);
|
||||
|
||||
s_djiLogFile = fopen(filePath, "wb+");
|
||||
if (s_djiLogFile == nullptr) {
|
||||
USER_LOG_ERROR("Open filepath time error.");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
if (logFileIndex >= DJI_LOG_MAX_COUNT) {
|
||||
sprintf(systemCmd, "rm -rf %s_%04d*.log", path, currentLogFileIndex - DJI_LOG_MAX_COUNT);
|
||||
ret = system(systemCmd);
|
||||
if (ret != 0) {
|
||||
printf("Remove file error, ret:%d.\r\n", ret);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
}
|
||||
|
||||
sprintf(systemCmd, "ln -sfrv %s " DJI_LOG_FOLDER_NAME "/latest.log", filePath);
|
||||
system(systemCmd);
|
||||
return djiReturnCode;
|
||||
}
|
||||
|
||||
static void DjiUser_NormalExitHandler(int signalNum)
|
||||
{
|
||||
USER_UTIL_UNUSED(signalNum);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
@ -0,0 +1,67 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_application.hpp
|
||||
* @brief This is the header file for "dji_application.cpp", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef APPLICATION_H
|
||||
#define APPLICATION_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
#include "dji_typedef.h"
|
||||
#include "dji_core.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
using namespace std;
|
||||
|
||||
class Application {
|
||||
public:
|
||||
Application(int argc, char **argv);
|
||||
~Application();
|
||||
|
||||
private:
|
||||
static void DjiUser_SetupEnvironment();
|
||||
static void DjiUser_ApplicationStart();
|
||||
static T_DjiReturnCode DjiUser_PrintConsole(const uint8_t *data, uint16_t dataLen);
|
||||
static T_DjiReturnCode DjiUser_LocalWrite(const uint8_t *data, uint16_t dataLen);
|
||||
static T_DjiReturnCode DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo);
|
||||
static T_DjiReturnCode DjiUser_LocalWriteFsInit(const char *path);
|
||||
};
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // APPLICATION_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
@ -0,0 +1,55 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_sdk_app_info.h
|
||||
* @brief This is the header file for defining the structure and (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2018 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef DJI_SDK_APP_INFO_H
|
||||
#define DJI_SDK_APP_INFO_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
// ATTENTION: User must goto https://developer.dji.com/user/apps/#all to create your own dji sdk application, get dji sdk application
|
||||
// information then fill in the application information here.
|
||||
#define USER_APP_NAME "your_app_name"
|
||||
#define USER_APP_ID "your_app_id"
|
||||
#define USER_APP_KEY "your_app_key"
|
||||
#define USER_APP_LICENSE "your_app_license"
|
||||
#define USER_DEVELOPER_ACCOUNT "your_developer_account"
|
||||
#define USER_BAUD_RATE "460800"
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // DJI_SDK_APP_INFO_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
@ -0,0 +1,56 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_sdk_config.h
|
||||
* @brief This is the header file for "dji_config.c", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef DJI_SDK_CONFIG_H
|
||||
#define DJI_SDK_CONFIG_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
#define DJI_USE_ONLY_UART (0)
|
||||
#define DJI_USE_UART_AND_USB_BULK_DEVICE (1)
|
||||
#define DJI_USE_UART_AND_NETWORK_DEVICE (2)
|
||||
#define DJI_USE_ONLY_USB_BULK_DEVICE (3)
|
||||
#define DJI_USE_ONLY_NETWORK_DEVICE (4)
|
||||
|
||||
/*!< Attention: Select your hardware connection mode here.
|
||||
* */
|
||||
#define CONFIG_HARDWARE_CONNECTION DJI_USE_ONLY_USB_BULK_DEVICE
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // DJI_SDK_CONFIG_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
145
samples/sample_c++/platform/linux/manifold3/application/main.cpp
Normal file
145
samples/sample_c++/platform/linux/manifold3/application/main.cpp
Normal file
@ -0,0 +1,145 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file main.cpp
|
||||
* @brief
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <liveview/test_liveview_entry.hpp>
|
||||
#include <perception/test_perception_entry.hpp>
|
||||
#include <perception/test_lidar_entry.hpp>
|
||||
#include <perception/test_radar_entry.hpp>
|
||||
#include <flight_control/test_flight_control.h>
|
||||
#include <gimbal/test_gimbal_entry.hpp>
|
||||
#include "application.hpp"
|
||||
#include "fc_subscription/test_fc_subscription.h"
|
||||
#include <gimbal_emu/test_payload_gimbal_emu.h>
|
||||
#include <camera_emu/test_payload_cam_emu_media.h>
|
||||
#include <camera_emu/test_payload_cam_emu_base.h>
|
||||
#include <dji_logger.h>
|
||||
#include "widget/test_widget.h"
|
||||
#include "widget/test_widget_speaker.h"
|
||||
#include <widget_manager/test_widget_manager.hpp>
|
||||
#include <power_management/test_power_management.h>
|
||||
#include "data_transmission/test_data_transmission.h"
|
||||
#include <flight_controller/test_flight_controller_entry.h>
|
||||
#include <positioning/test_positioning.h>
|
||||
#include <hms_manager/hms_manager_entry.h>
|
||||
#include "camera_manager/test_camera_manager_entry.h"
|
||||
#include <hms_manager/hms_manager_entry.h>
|
||||
#include <liveview/dji_liveview_object_detection.hpp>
|
||||
#include <signal.h>
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
signal(SIGINT, [](int signalNum) -> void { exit(0); });
|
||||
Application application(argc, argv);
|
||||
char inputChar;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
T_DjiReturnCode returnCode;
|
||||
|
||||
start:
|
||||
std::cout
|
||||
<< "\n"
|
||||
<< "| Available commands: |\n"
|
||||
<< "| [0] Fc subscribe sample - subscribe quaternion and gps data |\n"
|
||||
<< "| [1] Flight controller sample - you can control flying by PSDK |\n"
|
||||
<< "| [2] Hms info manager sample - get health manger system info by language |\n"
|
||||
<< "| [a] Gimbal manager sample - you can control gimbal by PSDK |\n"
|
||||
<< "| [d] Stereo vision view sample - display the stereo image |\n"
|
||||
<< "| [e] Run camera manager sample - you can test camera's functions interactively |\n"
|
||||
<< "| [f] Start rtk positioning sample - you can receive rtk rtcm data when rtk signal is ok |\n"
|
||||
<< "| [g] Request Lidar data sample - Request Lidar data and store the point cloud data as pcd files |\n"
|
||||
<< "| [h] Request Radar data sample - Request radar data |\n"
|
||||
<< "| [i] Run manifold3 AI sample - request h.264 bitstream data, codec it and display it on pilot |\n"
|
||||
<< "| [j] Run Hms Enhance sample - shake motor and play sound on pilot |\n"
|
||||
<< "| [l] Run widget states manager sample, control widget states on other payload |\n"
|
||||
<< "| [m] Run Open Ar sample - draw ar gragh\n"
|
||||
<< std::endl;
|
||||
|
||||
std::cin >> inputChar;
|
||||
switch (inputChar) {
|
||||
case '0':
|
||||
DjiTest_FcSubscriptionRunSample();
|
||||
break;
|
||||
case '1':
|
||||
DjiUser_RunFlightControllerSample();
|
||||
break;
|
||||
case '2':
|
||||
DjiUser_RunHmsManagerSample();
|
||||
break;
|
||||
case 'a':
|
||||
DjiUser_RunGimbalManagerSample();
|
||||
break;
|
||||
case 'd':
|
||||
DjiUser_RunStereoVisionViewSample();
|
||||
break;
|
||||
case 'e':
|
||||
DjiUser_RunCameraManagerSample();
|
||||
break;
|
||||
case 'f':
|
||||
returnCode = DjiTest_PositioningStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("rtk positioning sample init error");
|
||||
break;
|
||||
}
|
||||
USER_LOG_INFO("Start rtk positioning sample successfully");
|
||||
break;
|
||||
case 'g':
|
||||
DjiUser_RunLidarDataSubscriptionSample();
|
||||
break;
|
||||
case 'h':
|
||||
DjiUser_RunRadarDataSubscriptionSample();
|
||||
break;
|
||||
case 'i':
|
||||
DjiUser_RunCameraAiDetectionSample();
|
||||
break;
|
||||
case 'j':
|
||||
DjiUser_RunHmsEnhanceSample();
|
||||
break;
|
||||
case 'l':
|
||||
DjiTest_WidgetMannagerStart();
|
||||
break;
|
||||
case 'm':
|
||||
DjiUser_RunOpenArSample();
|
||||
break;
|
||||
case 'q':
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
osalHandler->TaskSleepMs(2000);
|
||||
|
||||
goto start;
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
252
samples/sample_c++/platform/linux/manifold3/hal/hal_usb_bulk.c
Normal file
252
samples/sample_c++/platform/linux/manifold3/hal/hal_usb_bulk.c
Normal file
@ -0,0 +1,252 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file hal_usb_bulk.c
|
||||
* @brief
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "hal_usb_bulk.h"
|
||||
#include "dji_logger.h"
|
||||
#include <errno.h>
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define LINUX_USB_BULK_TRANSFER_TIMEOUT_MS (50)
|
||||
#define LINUX_USB_BULK_TRANSFER_WAIT_FOREVER (-1)
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
typedef struct {
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
libusb_device_handle *handle;
|
||||
#else
|
||||
void *handle;
|
||||
#endif
|
||||
int32_t ep1;
|
||||
int32_t ep2;
|
||||
uint32_t interfaceNum;
|
||||
T_DjiHalUsbBulkInfo usbBulkInfo;
|
||||
} T_HalUsbBulkObj;
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHandle *usbBulkHandle)
|
||||
{
|
||||
int32_t ret;
|
||||
struct libusb_device_handle *handle = NULL;
|
||||
|
||||
*usbBulkHandle = malloc(sizeof(T_HalUsbBulkObj));
|
||||
if (*usbBulkHandle == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
if (usbBulkInfo.isUsbHost == true) {
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
ret = libusb_init(NULL);
|
||||
if (ret < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
handle = libusb_open_device_with_vid_pid(NULL, usbBulkInfo.vid, usbBulkInfo.pid);
|
||||
if (handle == NULL) {
|
||||
USER_LOG_ERROR("libusb open device error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
ret = libusb_claim_interface(handle, usbBulkInfo.channelInfo.interfaceNum);
|
||||
if (ret != LIBUSB_SUCCESS) {
|
||||
USER_LOG_ERROR("libusb claim interface error");
|
||||
libusb_close(handle);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle;
|
||||
memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo));
|
||||
#endif
|
||||
} else {
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle;
|
||||
memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo));
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->interfaceNum = usbBulkInfo.channelInfo.interfaceNum;
|
||||
|
||||
if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK1_INTERFACE_NUM) {
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK1_EP_IN_FD, O_RDWR);
|
||||
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK1_EP_OUT_FD, O_RDWR);
|
||||
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
} else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK2_INTERFACE_NUM) {
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK2_EP_IN_FD, O_RDWR);
|
||||
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK2_EP_OUT_FD, O_RDWR);
|
||||
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
} else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK3_INTERFACE_NUM) {
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK3_EP_IN_FD, O_RDWR);
|
||||
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK3_EP_OUT_FD, O_RDWR);
|
||||
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle)
|
||||
{
|
||||
struct libusb_device_handle *handle = NULL;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
|
||||
if (usbBulkHandle == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
||||
|
||||
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
libusb_release_interface(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum);
|
||||
osalHandler->TaskSleepMs(100);
|
||||
libusb_exit(NULL);
|
||||
#endif
|
||||
} else {
|
||||
close(((T_HalUsbBulkObj *) usbBulkHandle)->ep1);
|
||||
close(((T_HalUsbBulkObj *) usbBulkHandle)->ep2);
|
||||
}
|
||||
|
||||
free(usbBulkHandle);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUsbBulk_WriteData(T_DjiUsbBulkHandle usbBulkHandle, const uint8_t *buf, uint32_t len,
|
||||
uint32_t *realLen)
|
||||
{
|
||||
int32_t ret;
|
||||
int32_t actualLen;
|
||||
struct libusb_device_handle *handle = NULL;
|
||||
|
||||
if (usbBulkHandle == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
||||
|
||||
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointOut,
|
||||
(uint8_t *) buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_TIMEOUT_MS);
|
||||
if (ret < 0) {
|
||||
USER_LOG_ERROR("Write usb bulk data failed, errno = %d", ret);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
*realLen = actualLen;
|
||||
#endif
|
||||
} else {
|
||||
ret = write(((T_HalUsbBulkObj *) usbBulkHandle)->ep1, buf, len);
|
||||
if (ret < 0) {
|
||||
USER_LOG_ERROR("write ret %d %d %s\n", ret, errno, strerror(errno));
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
} else {
|
||||
*realLen = ret;
|
||||
}
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len,
|
||||
uint32_t *realLen)
|
||||
{
|
||||
int32_t ret;
|
||||
struct libusb_device_handle *handle = NULL;
|
||||
int32_t actualLen;
|
||||
|
||||
if (usbBulkHandle == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
||||
|
||||
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointIn,
|
||||
buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_WAIT_FOREVER);
|
||||
if (ret < 0) {
|
||||
USER_LOG_ERROR("Read usb bulk data failed, errno = %d", ret);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
*realLen = actualLen;
|
||||
#endif
|
||||
} else {
|
||||
ret = read(((T_HalUsbBulkObj *) usbBulkHandle)->ep2, buf, len);
|
||||
if (ret < 0) {
|
||||
USER_LOG_ERROR("read ret %d %d %s\n", ret, errno, strerror(errno));
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
} else {
|
||||
*realLen = ret;
|
||||
}
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo)
|
||||
{
|
||||
//attention: this interface only be called in usb device mode.
|
||||
deviceInfo->vid = LINUX_USB_VID;
|
||||
deviceInfo->pid = LINUX_USB_PID;
|
||||
|
||||
// This bulk channel is used to obtain DJI camera video stream and push 3rd-party camera video stream.
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].interfaceNum = LINUX_USB_BULK1_INTERFACE_NUM;
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].endPointIn = LINUX_USB_BULK1_END_POINT_IN;
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].endPointOut = LINUX_USB_BULK1_END_POINT_OUT;
|
||||
|
||||
// This bulk channel is used to obtain DJI perception image and download camera media file.
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].interfaceNum = LINUX_USB_BULK2_INTERFACE_NUM;
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointIn = LINUX_USB_BULK2_END_POINT_IN;
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointOut = LINUX_USB_BULK2_END_POINT_OUT;
|
||||
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].interfaceNum = LINUX_USB_BULK3_INTERFACE_NUM;
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointIn = LINUX_USB_BULK3_END_POINT_IN;
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointOut = LINUX_USB_BULK3_END_POINT_OUT;
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
@ -0,0 +1,93 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file hal_usb_bulk.h
|
||||
* @brief This is the header file for "hal_usb_bulk.c", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef HAL_USB_BULK_H
|
||||
#define HAL_USB_BULK_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "stdint.h"
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <termios.h>
|
||||
#include <unistd.h>
|
||||
#include <string.h>
|
||||
#include <sys/socket.h>
|
||||
#include <netinet/in.h>
|
||||
#include <arpa/inet.h>
|
||||
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
|
||||
#include <libusb-1.0/libusb.h>
|
||||
|
||||
#endif
|
||||
|
||||
#include "dji_platform.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
#define LINUX_USB_BULK1_EP_IN_FD "/dev/usb-ffs/bulk2/ep2"
|
||||
#define LINUX_USB_BULK1_EP_OUT_FD "/dev/usb-ffs/bulk2/ep1"
|
||||
|
||||
#define LINUX_USB_BULK1_INTERFACE_NUM (2)
|
||||
#define LINUX_USB_BULK1_END_POINT_IN (0x83)
|
||||
#define LINUX_USB_BULK1_END_POINT_OUT (0x02)
|
||||
|
||||
#define LINUX_USB_BULK2_EP_IN_FD "/dev/usb-ffs/bulk6/ep2"
|
||||
#define LINUX_USB_BULK2_EP_OUT_FD "/dev/usb-ffs/bulk6/ep1"
|
||||
|
||||
#define LINUX_USB_BULK2_INTERFACE_NUM (6)
|
||||
#define LINUX_USB_BULK2_END_POINT_IN (0x87)
|
||||
#define LINUX_USB_BULK2_END_POINT_OUT (0x06)
|
||||
|
||||
#define LINUX_USB_BULK3_EP_IN_FD "/dev/usb-ffs/bulk3/ep2"
|
||||
#define LINUX_USB_BULK3_EP_OUT_FD "/dev/usb-ffs/bulk3/ep1"
|
||||
|
||||
#define LINUX_USB_BULK3_INTERFACE_NUM (3)
|
||||
#define LINUX_USB_BULK3_END_POINT_IN (0x84)
|
||||
#define LINUX_USB_BULK3_END_POINT_OUT (0x03)
|
||||
|
||||
#define LINUX_USB_VID (0x2CA3)
|
||||
#define LINUX_USB_PID (0x3181)
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHandle *usbBulkHandle);
|
||||
T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle);
|
||||
T_DjiReturnCode HalUsbBulk_WriteData(T_DjiUsbBulkHandle usbBulkHandle, const uint8_t *buf, uint32_t len,
|
||||
uint32_t *realLen);
|
||||
T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len, uint32_t *realLen);
|
||||
T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // HAL_USB_BULK_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
@ -48,79 +48,80 @@ add_executable(${PROJECT_NAME}
|
||||
${MODULE_COMMON_SRC}
|
||||
${MODULE_HAL_SRC})
|
||||
|
||||
# Try to see if user has OpenCV installed
|
||||
# if yes, default callback will display the image
|
||||
find_package(OpenCV QUIET)
|
||||
if (OpenCV_FOUND)
|
||||
message("\n${PROJECT_NAME}...")
|
||||
message(STATUS "Found OpenCV installed in the system, will use it to display image in AdvancedSensing APIs")
|
||||
message(STATUS " - Includes: ${OpenCV_INCLUDE_DIRS}")
|
||||
message(STATUS " - Libraries: ${OpenCV_LIBRARIES}")
|
||||
# add_definitions(-DOPEN_CV_INSTALLED)
|
||||
# target_include_directories(${PROJECT_NAME} PRIVATE ${OpenCV_INCLUDE_DIRS})
|
||||
# target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS})
|
||||
else ()
|
||||
message(STATUS "Did not find OpenCV in the system, image data is inside RecvContainer as raw data")
|
||||
endif ()
|
||||
|
||||
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}")
|
||||
|
||||
EXECUTE_PROCESS(COMMAND ffmpeg -version
|
||||
OUTPUT_VARIABLE ffmpeg_version_output
|
||||
OUTPUT_STRIP_TRAILING_WHITESPACE
|
||||
)
|
||||
string(REGEX MATCH "version.*Copyright" ffmpeg_version_line ${ffmpeg_version_output})
|
||||
string(REGEX MATCH " .* " ffmpeg_version ${ffmpeg_version_line})
|
||||
string(REGEX MATCH "^ 5.*$" ffmpeg_major_version ${ffmpeg_version})
|
||||
|
||||
if (HEAD${ffmpeg_major_version} STREQUAL "HEAD")
|
||||
message(STATUS " - Version: ${ffmpeg_version}")
|
||||
else ()
|
||||
message(FATAL_ERROR " - Not support FFMPEG version: ${ffmpeg_major_version}, please install 4.x.x instead.")
|
||||
endif ()
|
||||
|
||||
# target_link_libraries(${PROJECT_NAME} ${FFMPEG_LIBRARIES})
|
||||
# include_directories(${FFMPEG_INCLUDE_DIR})
|
||||
# add_definitions(-DFFMPEG_INSTALLED)
|
||||
else ()
|
||||
message(STATUS "Cannot Find FFMPEG")
|
||||
endif (FFMPEG_FOUND)
|
||||
|
||||
include_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/include)
|
||||
|
||||
if (BUILD_CROSS_COMPILE MATCHES TRUE)
|
||||
# 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)
|
||||
target_include_directories(${PROJECT_NAME} PRIVATE ${OpenCV_INCLUDE_DIRS})
|
||||
target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS})
|
||||
else ()
|
||||
message(STATUS "Did not find OpenCV in the system, image data is inside RecvContainer as raw data")
|
||||
endif ()
|
||||
|
||||
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}")
|
||||
find_package(FFMPEG REQUIRED)
|
||||
if (FFMPEG_FOUND)
|
||||
message(STATUS "Found FFMPEG installed in the system")
|
||||
message(STATUS " - Includes: ${FFMPEG_INCLUDE_DIR}")
|
||||
message(STATUS " - Libraries: ${FFMPEG_LIBRARIES}")
|
||||
|
||||
# add_definitions(-DOPUS_INSTALLED)
|
||||
# target_link_libraries(${PROJECT_NAME} /usr/local/lib/libopus.a)
|
||||
else ()
|
||||
message(STATUS "Cannot Find OPUS")
|
||||
endif (OPUS_FOUND)
|
||||
EXECUTE_PROCESS(COMMAND ffmpeg -version
|
||||
OUTPUT_VARIABLE ffmpeg_version_output
|
||||
OUTPUT_STRIP_TRAILING_WHITESPACE
|
||||
)
|
||||
string(REGEX MATCH "version.*Copyright" ffmpeg_version_line ${ffmpeg_version_output})
|
||||
string(REGEX MATCH " .* " ffmpeg_version ${ffmpeg_version_line})
|
||||
string(REGEX MATCH "^ 5.*$" ffmpeg_major_version ${ffmpeg_version})
|
||||
|
||||
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}")
|
||||
if (HEAD${ffmpeg_major_version} STREQUAL "HEAD")
|
||||
message(STATUS " - Version: ${ffmpeg_version}")
|
||||
else ()
|
||||
message(FATAL_ERROR " - Not support FFMPEG version: ${ffmpeg_major_version}, please install 4.x.x instead.")
|
||||
endif ()
|
||||
|
||||
# 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} ${FFMPEG_LIBRARIES})
|
||||
include_directories(${FFMPEG_INCLUDE_DIR})
|
||||
add_definitions(-DFFMPEG_INSTALLED)
|
||||
else ()
|
||||
message(STATUS "Cannot Find FFMPEG")
|
||||
endif (FFMPEG_FOUND)
|
||||
|
||||
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)
|
||||
endif ()
|
||||
|
||||
if (NOT EXECUTABLE_OUTPUT_PATH)
|
||||
set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
|
||||
endif ()
|
||||
|
||||
target_link_libraries(${PROJECT_NAME} m)
|
||||
target_link_libraries(${PROJECT_NAME} dl)
|
||||
|
||||
add_dependencies(${PROJECT_NAME} djisdk)
|
||||
@ -132,6 +132,7 @@ void Application::DjiUser_SetupEnvironment()
|
||||
uartHandler.UartWriteData = HalUart_WriteData;
|
||||
uartHandler.UartReadData = HalUart_ReadData;
|
||||
uartHandler.UartGetStatus = HalUart_GetStatus;
|
||||
uartHandler.UartGetDeviceInfo = HalUart_GetDeviceInfo;
|
||||
|
||||
usbBulkHandler.UsbBulkInit = HalUsbBulk_Init;
|
||||
usbBulkHandler.UsbBulkDeInit = HalUsbBulk_DeInit;
|
||||
@ -184,6 +185,23 @@ void Application::DjiUser_SetupEnvironment()
|
||||
throw std::runtime_error("Register hal network handler error");
|
||||
}
|
||||
|
||||
#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_USB_BULK_DEVICE)
|
||||
returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Register hal network handler error");
|
||||
}
|
||||
|
||||
#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_NETWORK_DEVICE)
|
||||
returnCode = DjiPlatform_RegHalNetworkHandler(&networkHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Register hal network handler error");
|
||||
}
|
||||
|
||||
//Attention: if you want to use camera stream view function, please uncomment it.
|
||||
returnCode = DjiPlatform_RegSocketHandler(&socketHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("register osal socket handler error");
|
||||
}
|
||||
#endif
|
||||
|
||||
returnCode = DjiPlatform_RegFileSystemHandler(&fileSystemHandler);
|
||||
@ -236,8 +254,10 @@ void Application::DjiUser_ApplicationStart()
|
||||
throw std::runtime_error("Get aircraft base info error.");
|
||||
}
|
||||
|
||||
if (aircraftInfoBaseInfo.mountPosition != DJI_MOUNT_POSITION_EXTENSION_PORT) {
|
||||
throw std::runtime_error("Please run this sample on extension port.");
|
||||
if (aircraftInfoBaseInfo.mountPosition != DJI_MOUNT_POSITION_EXTENSION_PORT &&
|
||||
aircraftInfoBaseInfo.djiAdapterType != DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE &&
|
||||
aircraftInfoBaseInfo.djiAdapterType != DJI_SDK_ADAPTER_TYPE_SKYPORT_V3) {
|
||||
throw std::runtime_error("Please run this sample on extension port or skyport v3.");
|
||||
}
|
||||
|
||||
returnCode = DjiCore_SetAlias("PSDK_APPALIAS");
|
||||
@ -313,7 +333,7 @@ T_DjiReturnCode Application::DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo)
|
||||
!strcmp(USER_DEVELOPER_ACCOUNT, "your_developer_account") ||
|
||||
!strcmp(USER_BAUD_RATE, "your_baud_rate")) {
|
||||
USER_LOG_ERROR(
|
||||
"Please fill in correct user information to 'samples/sample_c++/platform/linux/manifold2/application/dji_sdk_app_info.h' file.");
|
||||
"Please fill in correct user information to 'samples/sample_c++/platform/linux/nvidia_jetson/application/dji_sdk_app_info.h' file.");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
|
||||
@ -37,10 +37,12 @@ extern "C" {
|
||||
#define DJI_USE_ONLY_UART (0)
|
||||
#define DJI_USE_UART_AND_USB_BULK_DEVICE (1)
|
||||
#define DJI_USE_UART_AND_NETWORK_DEVICE (2)
|
||||
#define DJI_USE_ONLY_USB_BULK_DEVICE (3)
|
||||
#define DJI_USE_ONLY_NETWORK_DEVICE (4)
|
||||
|
||||
/*!< Attention: Select your hardware connection mode here.
|
||||
* */
|
||||
#define CONFIG_HARDWARE_CONNECTION DJI_USE_ONLY_UART
|
||||
#define CONFIG_HARDWARE_CONNECTION DJI_USE_ONLY_USB_BULK_DEVICE
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
|
||||
@ -25,6 +25,8 @@
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <liveview/test_liveview_entry.hpp>
|
||||
#include <perception/test_perception_entry.hpp>
|
||||
#include <perception/test_lidar_entry.hpp>
|
||||
#include <perception/test_radar_entry.hpp>
|
||||
#include <flight_control/test_flight_control.h>
|
||||
#include <gimbal/test_gimbal_entry.hpp>
|
||||
#include "application.hpp"
|
||||
@ -42,8 +44,6 @@
|
||||
#include <hms_manager/hms_manager_entry.h>
|
||||
#include "camera_manager/test_camera_manager_entry.h"
|
||||
#include <hms_manager/hms_manager_entry.h>
|
||||
#include "waypoint_v2/test_waypoint_v2.h"
|
||||
#include "waypoint_v3/test_waypoint_v3.h"
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
|
||||
@ -74,6 +74,8 @@ start:
|
||||
<< "| [d] Stereo vision view sample - display the stereo image |\n"
|
||||
<< "| [e] Run camera manager sample - you can test camera's functions interactively |\n"
|
||||
<< "| [f] Start rtk positioning sample - you can receive rtk rtcm data when rtk signal is ok |\n"
|
||||
<< "| [g] Request Lidar data sample - Request Lidar data and store the point cloud data as pcd files |\n"
|
||||
<< "| [h] Request Radar data sample - Request radar data |\n"
|
||||
<< std::endl;
|
||||
|
||||
std::cin >> inputChar;
|
||||
@ -103,10 +105,10 @@ start:
|
||||
DjiUser_RunHmsManagerSample();
|
||||
break;
|
||||
case '8':
|
||||
DjiTest_WaypointV2RunSample();
|
||||
// DjiTest_WaypointV2RunSample();
|
||||
break;
|
||||
case '9':
|
||||
DjiTest_WaypointV3RunSample();
|
||||
// DjiTest_WaypointV3RunSample();
|
||||
break;
|
||||
case 'a':
|
||||
DjiUser_RunGimbalManagerSample();
|
||||
@ -129,6 +131,12 @@ start:
|
||||
|
||||
USER_LOG_INFO("Start rtk positioning sample successfully");
|
||||
break;
|
||||
case 'g':
|
||||
DjiUser_RunLidarDataSubscriptionSample();
|
||||
break;
|
||||
case 'h':
|
||||
DjiUser_RunRadarDataSubscriptionSample();
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
@ -255,6 +255,18 @@ T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *stat
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo)
|
||||
{
|
||||
if (deviceInfo == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
deviceInfo->vid = USB_UART_CONNECTED_TO_UAV_VID;
|
||||
deviceInfo->pid = USB_UART_CONNECTED_TO_UAV_PID;
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
|
||||
@ -48,6 +48,15 @@ extern "C" {
|
||||
#define LINUX_UART_DEV1 "/dev/ttyUSB0"
|
||||
#define LINUX_UART_DEV2 "/dev/ttyACM0"
|
||||
|
||||
/**
|
||||
* Use for Eport 2.0, specify the VID and PID of the USB serial port closest to the aircraft.
|
||||
* FT232 0x0403:0x6001
|
||||
* CP2102 0x10C4:0xEA60
|
||||
* VCOM 0x2CA3:0xF002
|
||||
*/
|
||||
#define USB_UART_CONNECTED_TO_UAV_VID (0x0403)
|
||||
#define USB_UART_CONNECTED_TO_UAV_PID (0x6001)
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
@ -56,6 +65,7 @@ T_DjiReturnCode HalUart_DeInit(T_DjiUartHandle uartHandle);
|
||||
T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf, uint32_t len, uint32_t *realLen);
|
||||
T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen);
|
||||
T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *status);
|
||||
T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
||||
@ -107,6 +107,16 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan
|
||||
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
} else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK3_INTERFACE_NUM) {
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK3_EP_IN_FD, O_RDWR);
|
||||
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK3_EP_OUT_FD, O_RDWR);
|
||||
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -230,6 +240,10 @@ T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo)
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointIn = LINUX_USB_BULK2_END_POINT_IN;
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointOut = LINUX_USB_BULK2_END_POINT_OUT;
|
||||
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].interfaceNum = LINUX_USB_BULK3_INTERFACE_NUM;
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointIn = LINUX_USB_BULK3_END_POINT_IN;
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointOut = LINUX_USB_BULK3_END_POINT_OUT;
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
|
||||
@ -66,12 +66,19 @@ extern "C" {
|
||||
#define LINUX_USB_BULK2_END_POINT_IN (0x82)
|
||||
#define LINUX_USB_BULK2_END_POINT_OUT (0x02)
|
||||
|
||||
#define LINUX_USB_BULK3_EP_IN_FD "/dev/usb-ffs/bulk3/ep1"
|
||||
#define LINUX_USB_BULK3_EP_OUT_FD "/dev/usb-ffs/bulk3/ep2"
|
||||
|
||||
#define LINUX_USB_BULK3_INTERFACE_NUM (2)
|
||||
#define LINUX_USB_BULK3_END_POINT_IN (0x83)
|
||||
#define LINUX_USB_BULK3_END_POINT_OUT (0x03)
|
||||
|
||||
#ifdef PLATFORM_ARCH_x86_64
|
||||
#define LINUX_USB_VID (0x0B95)
|
||||
#define LINUX_USB_PID (0x1790)
|
||||
#else
|
||||
#define LINUX_USB_VID (0x0955)
|
||||
#define LINUX_USB_PID (0x7020)
|
||||
#define LINUX_USB_VID (0x2CA3)
|
||||
#define LINUX_USB_PID (0xF001)
|
||||
#endif
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
132
samples/sample_c++/platform/linux/raspberry_pi/CMakeLists.txt
Normal file
132
samples/sample_c++/platform/linux/raspberry_pi/CMakeLists.txt
Normal file
@ -0,0 +1,132 @@
|
||||
cmake_minimum_required(VERSION 3.5)
|
||||
project(dji_sdk_demo_on_rpi_cxx CXX)
|
||||
|
||||
set(CMAKE_C_FLAGS "-pthread -std=gnu99")
|
||||
set(CMAKE_CXX_FLAGS "-std=c++11 -pthread")
|
||||
set(CMAKE_EXE_LINKER_FLAGS "-pthread")
|
||||
set(CMAKE_C_COMPILER "aarch64-linux-gnu-gcc")
|
||||
set(CMAKE_CXX_COMPILER "aarch64-linux-gnu-g++")
|
||||
add_definitions(-D_GNU_SOURCE)
|
||||
|
||||
if (MEMORY_LEAK_CHECK_ON MATCHES TRUE)
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fsanitize=leak")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fsanitize=leak")
|
||||
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -lasan")
|
||||
endif ()
|
||||
|
||||
if (BUILD_TEST_CASES_ON MATCHES TRUE)
|
||||
set(COMMON_CXX_FLAGS "-std=c++11 -pthread")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fprofile-arcs -ftest-coverage -Wno-deprecated-declarations")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fprofile-arcs -ftest-coverage")
|
||||
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -fprofile-arcs -ftest-coverage -lgcov")
|
||||
endif ()
|
||||
|
||||
include_directories(../../../module_sample)
|
||||
include_directories(../../../../sample_c/module_sample)
|
||||
include_directories(../common)
|
||||
include_directories(application)
|
||||
|
||||
file(GLOB_RECURSE MODULE_SAMPLE_SRC
|
||||
../../../module_sample/liveview/*.c*
|
||||
../../../module_sample/camera_manager/*.c*
|
||||
../../../module_sample/perception/*.c*
|
||||
../../../module_sample/gimbal/*.c*
|
||||
../../../module_sample/flight_controller/*.c*
|
||||
../../../module_sample/hms_manager/*.c*
|
||||
../../../../sample_c/module_sample/*.c
|
||||
../../../module_sample/widget_manager/*.c*
|
||||
)
|
||||
file(GLOB_RECURSE MODULE_COMMON_SRC ../common/*.c*)
|
||||
file(GLOB_RECURSE MODULE_HAL_SRC hal/*.c*)
|
||||
file(GLOB_RECURSE MODULE_APP_SRC application/*.c*)
|
||||
|
||||
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/../common/3rdparty)
|
||||
|
||||
link_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/lib/aarch64-linux-gnu-gcc)
|
||||
link_libraries(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/lib/aarch64-linux-gnu-gcc/libpayloadsdk.a -lstdc++)
|
||||
|
||||
add_executable(${PROJECT_NAME}
|
||||
${MODULE_APP_SRC}
|
||||
${MODULE_SAMPLE_SRC}
|
||||
${MODULE_COMMON_SRC}
|
||||
${MODULE_HAL_SRC})
|
||||
|
||||
include_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/include)
|
||||
|
||||
if (BUILD_CROSS_COMPILE MATCHES TRUE)
|
||||
# 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}")
|
||||
|
||||
EXECUTE_PROCESS(COMMAND ffmpeg -version
|
||||
OUTPUT_VARIABLE ffmpeg_version_output
|
||||
OUTPUT_STRIP_TRAILING_WHITESPACE
|
||||
)
|
||||
string(REGEX MATCH "version.*Copyright" ffmpeg_version_line ${ffmpeg_version_output})
|
||||
string(REGEX MATCH " .* " ffmpeg_version ${ffmpeg_version_line})
|
||||
string(REGEX MATCH "^ 5.*$" ffmpeg_major_version ${ffmpeg_version})
|
||||
|
||||
if (HEAD${ffmpeg_major_version} STREQUAL "HEAD")
|
||||
message(STATUS " - Version: ${ffmpeg_version}")
|
||||
else ()
|
||||
message(FATAL_ERROR " - Not support FFMPEG version: ${ffmpeg_major_version}, please install 4.x.x instead.")
|
||||
endif ()
|
||||
|
||||
target_link_libraries(${PROJECT_NAME} ${FFMPEG_LIBRARIES})
|
||||
include_directories(${FFMPEG_INCLUDE_DIR})
|
||||
add_definitions(-DFFMPEG_INSTALLED)
|
||||
else ()
|
||||
message(STATUS "Cannot Find FFMPEG")
|
||||
endif (FFMPEG_FOUND)
|
||||
|
||||
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)
|
||||
endif()
|
||||
|
||||
if (NOT EXECUTABLE_OUTPUT_PATH)
|
||||
set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
|
||||
endif ()
|
||||
|
||||
target_link_libraries(${PROJECT_NAME} m dl)
|
||||
|
||||
target_include_directories(${PROJECT_NAME} PRIVATE ${OpenCV_INCLUDE_DIRS})
|
||||
if (OpenCV_FOUND)
|
||||
target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS})
|
||||
endif ()
|
||||
|
||||
@ -0,0 +1,542 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file application.cpp
|
||||
* @brief
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "application.hpp"
|
||||
#include "dji_sdk_app_info.h"
|
||||
#include <dji_platform.h>
|
||||
#include <dji_logger.h>
|
||||
#include <dji_core.h>
|
||||
#include <dji_aircraft_info.h>
|
||||
#include <csignal>
|
||||
#include "dji_sdk_config.h"
|
||||
|
||||
#include "../common/osal/osal.h"
|
||||
#include "../common/osal/osal_fs.h"
|
||||
#include "../common/osal/osal_socket.h"
|
||||
#include "../hal/hal_usb_bulk.h"
|
||||
#include "../hal/hal_uart.h"
|
||||
#include "../hal/hal_network.h"
|
||||
#include "../hal/hal_i2c.h"
|
||||
|
||||
#include <gimbal_emu/test_payload_gimbal_emu.h>
|
||||
#include <camera_emu/test_payload_cam_emu_media.h>
|
||||
#include <camera_emu/test_payload_cam_emu_base.h>
|
||||
#include "widget/test_widget.h"
|
||||
#include "widget/test_widget_speaker.h"
|
||||
#include <power_management/test_power_management.h>
|
||||
#include "data_transmission/test_data_transmission.h"
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define DJI_LOG_PATH "Logs/DJI"
|
||||
#define DJI_LOG_INDEX_FILE_NAME "Logs/index"
|
||||
#define DJI_LOG_FOLDER_NAME "Logs"
|
||||
#define DJI_LOG_PATH_MAX_SIZE (128)
|
||||
#define DJI_LOG_FOLDER_NAME_MAX_SIZE (32)
|
||||
#define DJI_SYSTEM_CMD_STR_MAX_SIZE (64)
|
||||
#define DJI_LOG_MAX_COUNT (10)
|
||||
|
||||
#define USER_UTIL_UNUSED(x) ((x) = (x))
|
||||
#define USER_UTIL_MIN(a, b) (((a) < (b)) ? (a) : (b))
|
||||
#define USER_UTIL_MAX(a, b) (((a) > (b)) ? (a) : (b))
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
static FILE *s_djiLogFile;
|
||||
static FILE *s_djiLogFileCnt;
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
static void DjiUser_NormalExitHandler(int signalNum);
|
||||
static T_DjiReturnCode DjiTest_HighPowerApplyPinInit();
|
||||
static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState);
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
Application::Application(int argc, char **argv)
|
||||
{
|
||||
Application::DjiUser_SetupEnvironment();
|
||||
Application::DjiUser_ApplicationStart();
|
||||
|
||||
Osal_TaskSleepMs(3000);
|
||||
}
|
||||
|
||||
Application::~Application()
|
||||
= default;
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
void Application::DjiUser_SetupEnvironment()
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiOsalHandler osalHandler = {0};
|
||||
T_DjiHalUartHandler uartHandler = {0};
|
||||
T_DjiHalUsbBulkHandler usbBulkHandler = {0};
|
||||
T_DjiLoggerConsole printConsole;
|
||||
T_DjiLoggerConsole localRecordConsole;
|
||||
T_DjiFileSystemHandler fileSystemHandler = {0};
|
||||
T_DjiSocketHandler socketHandler{0};
|
||||
T_DjiHalNetworkHandler networkHandler = {0};
|
||||
T_DjiHalI2cHandler i2CHandler = {0};
|
||||
|
||||
networkHandler.NetworkInit = HalNetWork_Init;
|
||||
networkHandler.NetworkDeInit = HalNetWork_DeInit;
|
||||
networkHandler.NetworkGetDeviceInfo = HalNetWork_GetDeviceInfo;
|
||||
|
||||
socketHandler.Socket = Osal_Socket;
|
||||
socketHandler.Bind = Osal_Bind;
|
||||
socketHandler.Close = Osal_Close;
|
||||
socketHandler.UdpSendData = Osal_UdpSendData;
|
||||
socketHandler.UdpRecvData = Osal_UdpRecvData;
|
||||
socketHandler.TcpListen = Osal_TcpListen;
|
||||
socketHandler.TcpAccept = Osal_TcpAccept;
|
||||
socketHandler.TcpConnect = Osal_TcpConnect;
|
||||
socketHandler.TcpSendData = Osal_TcpSendData;
|
||||
socketHandler.TcpRecvData = Osal_TcpRecvData;
|
||||
|
||||
osalHandler.TaskCreate = Osal_TaskCreate;
|
||||
osalHandler.TaskDestroy = Osal_TaskDestroy;
|
||||
osalHandler.TaskSleepMs = Osal_TaskSleepMs;
|
||||
osalHandler.MutexCreate = Osal_MutexCreate;
|
||||
osalHandler.MutexDestroy = Osal_MutexDestroy;
|
||||
osalHandler.MutexLock = Osal_MutexLock;
|
||||
osalHandler.MutexUnlock = Osal_MutexUnlock;
|
||||
osalHandler.SemaphoreCreate = Osal_SemaphoreCreate;
|
||||
osalHandler.SemaphoreDestroy = Osal_SemaphoreDestroy;
|
||||
osalHandler.SemaphoreWait = Osal_SemaphoreWait;
|
||||
osalHandler.SemaphoreTimedWait = Osal_SemaphoreTimedWait;
|
||||
osalHandler.SemaphorePost = Osal_SemaphorePost;
|
||||
osalHandler.Malloc = Osal_Malloc;
|
||||
osalHandler.Free = Osal_Free;
|
||||
osalHandler.GetTimeMs = Osal_GetTimeMs;
|
||||
osalHandler.GetTimeUs = Osal_GetTimeUs;
|
||||
osalHandler.GetRandomNum = Osal_GetRandomNum;
|
||||
|
||||
printConsole.func = DjiUser_PrintConsole;
|
||||
printConsole.consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_INFO;
|
||||
printConsole.isSupportColor = true;
|
||||
|
||||
localRecordConsole.consoleLevel = DJI_LOGGER_CONSOLE_LOG_LEVEL_DEBUG;
|
||||
localRecordConsole.func = DjiUser_LocalWrite;
|
||||
localRecordConsole.isSupportColor = false;
|
||||
|
||||
uartHandler.UartInit = HalUart_Init;
|
||||
uartHandler.UartDeInit = HalUart_DeInit;
|
||||
uartHandler.UartWriteData = HalUart_WriteData;
|
||||
uartHandler.UartReadData = HalUart_ReadData;
|
||||
uartHandler.UartGetStatus = HalUart_GetStatus;
|
||||
uartHandler.UartGetDeviceInfo = HalUart_GetDeviceInfo;
|
||||
|
||||
i2CHandler.I2cInit = HalI2c_Init;
|
||||
i2CHandler.I2cDeInit = HalI2c_DeInit;
|
||||
i2CHandler.I2cWriteData = HalI2c_WriteData;
|
||||
i2CHandler.I2cReadData = HalI2c_ReadData;
|
||||
|
||||
usbBulkHandler.UsbBulkInit = HalUsbBulk_Init;
|
||||
usbBulkHandler.UsbBulkDeInit = HalUsbBulk_DeInit;
|
||||
usbBulkHandler.UsbBulkWriteData = HalUsbBulk_WriteData;
|
||||
usbBulkHandler.UsbBulkReadData = HalUsbBulk_ReadData;
|
||||
usbBulkHandler.UsbBulkGetDeviceInfo = HalUsbBulk_GetDeviceInfo;
|
||||
|
||||
fileSystemHandler.FileOpen = Osal_FileOpen,
|
||||
fileSystemHandler.FileClose = Osal_FileClose,
|
||||
fileSystemHandler.FileWrite = Osal_FileWrite,
|
||||
fileSystemHandler.FileRead = Osal_FileRead,
|
||||
fileSystemHandler.FileSync = Osal_FileSync,
|
||||
fileSystemHandler.FileSeek = Osal_FileSeek,
|
||||
fileSystemHandler.DirOpen = Osal_DirOpen,
|
||||
fileSystemHandler.DirClose = Osal_DirClose,
|
||||
fileSystemHandler.DirRead = Osal_DirRead,
|
||||
fileSystemHandler.Mkdir = Osal_Mkdir,
|
||||
fileSystemHandler.Unlink = Osal_Unlink,
|
||||
fileSystemHandler.Rename = Osal_Rename,
|
||||
fileSystemHandler.Stat = Osal_Stat,
|
||||
|
||||
returnCode = DjiPlatform_RegOsalHandler(&osalHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Register osal handler error.");
|
||||
}
|
||||
|
||||
returnCode = DjiPlatform_RegHalI2cHandler(&i2CHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("register hal i2c handler error");
|
||||
}
|
||||
|
||||
#if (CONFIG_HARDWARE_CONNECTION == DJI_USE_UART_AND_USB_BULK_DEVICE)
|
||||
returnCode = DjiPlatform_RegHalUartHandler(&uartHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Register hal uart handler error.");
|
||||
}
|
||||
|
||||
returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Register hal usb bulk handler error.");
|
||||
}
|
||||
#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_UART_AND_NETWORK_DEVICE)
|
||||
returnCode = DjiPlatform_RegHalUartHandler(&uartHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Register hal uart handler error.");
|
||||
}
|
||||
|
||||
returnCode = DjiPlatform_RegHalNetworkHandler(&networkHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Register hal network handler error");
|
||||
}
|
||||
#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_USB_BULK_DEVICE)
|
||||
returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Register hal network handler error");
|
||||
}
|
||||
|
||||
#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_NETWORK_DEVICE)
|
||||
returnCode = DjiPlatform_RegHalNetworkHandler(&networkHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Register hal network handler error");
|
||||
}
|
||||
|
||||
//Attention: if you want to use camera stream view function, please uncomment it.
|
||||
returnCode = DjiPlatform_RegSocketHandler(&socketHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("register osal socket handler error");
|
||||
}
|
||||
#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_UART)
|
||||
/*!< Attention: Only use uart hardware connection.
|
||||
*/
|
||||
returnCode = DjiPlatform_RegHalUartHandler(&uartHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Register hal uart handler error.");
|
||||
}
|
||||
#endif
|
||||
|
||||
//Attention: if you want to use camera stream view function, please uncomment it.
|
||||
returnCode = DjiPlatform_RegSocketHandler(&socketHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("register osal socket handler error");
|
||||
}
|
||||
|
||||
returnCode = DjiPlatform_RegFileSystemHandler(&fileSystemHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Register osal filesystem handler error.");
|
||||
}
|
||||
|
||||
if (DjiUser_LocalWriteFsInit(DJI_LOG_PATH) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("File system init error.");
|
||||
}
|
||||
|
||||
returnCode = DjiLogger_AddConsole(&printConsole);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Add printf console error.");
|
||||
}
|
||||
|
||||
returnCode = DjiLogger_AddConsole(&localRecordConsole);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Add printf console error.");
|
||||
}
|
||||
}
|
||||
|
||||
void Application::DjiUser_ApplicationStart()
|
||||
{
|
||||
T_DjiUserInfo userInfo;
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo;
|
||||
T_DjiFirmwareVersion firmwareVersion = {
|
||||
.majorVersion = 1,
|
||||
.minorVersion = 0,
|
||||
.modifyVersion = 0,
|
||||
.debugVersion = 0,
|
||||
};
|
||||
|
||||
// attention: when the program is hand up ctrl-c will generate the coredump file
|
||||
signal(SIGTERM, DjiUser_NormalExitHandler);
|
||||
|
||||
returnCode = DjiUser_FillInUserInfo(&userInfo);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Fill user info error, please check user info config.");
|
||||
}
|
||||
|
||||
returnCode = DjiCore_SetFirmwareVersion(firmwareVersion);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Set firmware version error.");
|
||||
}
|
||||
|
||||
returnCode = DjiCore_SetSerialNumber("PSDK12345678XX");
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Set serial number error");
|
||||
}
|
||||
|
||||
returnCode = DjiCore_Init(&userInfo);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
sleep(1);
|
||||
throw std::runtime_error("Core init error.");
|
||||
}
|
||||
|
||||
returnCode = DjiAircraftInfo_GetBaseInfo(&aircraftInfoBaseInfo);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Get aircraft base info error.");
|
||||
}
|
||||
|
||||
if (aircraftInfoBaseInfo.mountPosition != DJI_MOUNT_POSITION_EXTENSION_PORT &&
|
||||
aircraftInfoBaseInfo.djiAdapterType != DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE &&
|
||||
aircraftInfoBaseInfo.djiAdapterType != DJI_SDK_ADAPTER_TYPE_SKYPORT_V3) {
|
||||
throw std::runtime_error("Please run this sample on extension port or skyport v3.");
|
||||
}
|
||||
|
||||
returnCode = DjiCore_SetAlias("PSDK_APPALIAS");
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Set alias error.");
|
||||
}
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_CAMERA_EMU_ON
|
||||
returnCode = DjiTest_CameraEmuBaseStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("camera emu common init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_CAMERA_MEDIA_ON
|
||||
returnCode = DjiTest_CameraEmuMediaStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("camera emu media init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON
|
||||
returnCode = DjiTest_GimbalStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("psdk gimbal init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_WIDGET_ON
|
||||
returnCode = DjiTest_WidgetStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("widget sample init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_WIDGET_SPEAKER_ON
|
||||
returnCode = DjiTest_WidgetSpeakerStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("widget speaker test init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_POWER_MANAGEMENT_ON
|
||||
T_DjiTestApplyHighPowerHandler applyHighPowerHandler = {
|
||||
.pinInit = DjiTest_HighPowerApplyPinInit,
|
||||
.pinWrite = DjiTest_WriteHighPowerApplyPin,
|
||||
};
|
||||
|
||||
returnCode = DjiTest_RegApplyHighPowerHandler(&applyHighPowerHandler);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("regsiter apply high power handler error");
|
||||
}
|
||||
|
||||
returnCode = DjiTest_PowerManagementStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("power management init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MODULE_SAMPLE_DATA_TRANSMISSION_ON
|
||||
returnCode = DjiTest_DataTransmissionStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("widget sample init error");
|
||||
}
|
||||
#endif
|
||||
|
||||
returnCode = DjiCore_ApplicationStart();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
throw std::runtime_error("Start sdk application error.");
|
||||
}
|
||||
|
||||
USER_LOG_INFO("Application start.");
|
||||
}
|
||||
|
||||
T_DjiReturnCode Application::DjiUser_PrintConsole(const uint8_t *data, uint16_t dataLen)
|
||||
{
|
||||
printf("%s", data);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode Application::DjiUser_LocalWrite(const uint8_t *data, uint16_t dataLen)
|
||||
{
|
||||
int32_t realLen;
|
||||
|
||||
if (s_djiLogFile == nullptr) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
}
|
||||
|
||||
realLen = fwrite(data, 1, dataLen, s_djiLogFile);
|
||||
fflush(s_djiLogFile);
|
||||
if (realLen == dataLen) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
} else {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
}
|
||||
}
|
||||
|
||||
T_DjiReturnCode Application::DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo)
|
||||
{
|
||||
memset(userInfo->appName, 0, sizeof(userInfo->appName));
|
||||
memset(userInfo->appId, 0, sizeof(userInfo->appId));
|
||||
memset(userInfo->appKey, 0, sizeof(userInfo->appKey));
|
||||
memset(userInfo->appLicense, 0, sizeof(userInfo->appLicense));
|
||||
memset(userInfo->developerAccount, 0, sizeof(userInfo->developerAccount));
|
||||
memset(userInfo->baudRate, 0, sizeof(userInfo->baudRate));
|
||||
|
||||
if (strlen(USER_APP_NAME) >= sizeof(userInfo->appName) ||
|
||||
strlen(USER_APP_ID) > sizeof(userInfo->appId) ||
|
||||
strlen(USER_APP_KEY) > sizeof(userInfo->appKey) ||
|
||||
strlen(USER_APP_LICENSE) > sizeof(userInfo->appLicense) ||
|
||||
strlen(USER_DEVELOPER_ACCOUNT) >= sizeof(userInfo->developerAccount) ||
|
||||
strlen(USER_BAUD_RATE) > sizeof(userInfo->baudRate)) {
|
||||
USER_LOG_ERROR("Length of user information string is beyond limit. Please check.");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
if (!strcmp(USER_APP_NAME, "your_app_name") ||
|
||||
!strcmp(USER_APP_ID, "your_app_id") ||
|
||||
!strcmp(USER_APP_KEY, "your_app_key") ||
|
||||
!strcmp(USER_BAUD_RATE, "your_app_license") ||
|
||||
!strcmp(USER_DEVELOPER_ACCOUNT, "your_developer_account") ||
|
||||
!strcmp(USER_BAUD_RATE, "your_baud_rate")) {
|
||||
USER_LOG_ERROR(
|
||||
"Please fill in correct user information to 'samples/sample_c++/platform/linux/manifold2/application/dji_sdk_app_info.h' file.");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
strncpy(userInfo->appName, USER_APP_NAME, sizeof(userInfo->appName) - 1);
|
||||
memcpy(userInfo->appId, USER_APP_ID, USER_UTIL_MIN(sizeof(userInfo->appId), strlen(USER_APP_ID)));
|
||||
memcpy(userInfo->appKey, USER_APP_KEY, USER_UTIL_MIN(sizeof(userInfo->appKey), strlen(USER_APP_KEY)));
|
||||
memcpy(userInfo->appLicense, USER_APP_LICENSE,
|
||||
USER_UTIL_MIN(sizeof(userInfo->appLicense), strlen(USER_APP_LICENSE)));
|
||||
memcpy(userInfo->baudRate, USER_BAUD_RATE, USER_UTIL_MIN(sizeof(userInfo->baudRate), strlen(USER_BAUD_RATE)));
|
||||
strncpy(userInfo->developerAccount, USER_DEVELOPER_ACCOUNT, sizeof(userInfo->developerAccount) - 1);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode Application::DjiUser_LocalWriteFsInit(const char *path)
|
||||
{
|
||||
T_DjiReturnCode djiReturnCode = DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
char filePath[DJI_LOG_PATH_MAX_SIZE];
|
||||
char systemCmd[DJI_SYSTEM_CMD_STR_MAX_SIZE];
|
||||
char folderName[DJI_LOG_FOLDER_NAME_MAX_SIZE];
|
||||
time_t currentTime = time(nullptr);
|
||||
struct tm *localTime = localtime(¤tTime);
|
||||
uint16_t logFileIndex = 0;
|
||||
uint16_t currentLogFileIndex;
|
||||
uint8_t ret;
|
||||
|
||||
if (localTime == nullptr) {
|
||||
printf("Get local time error.\r\n");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
if (access(DJI_LOG_FOLDER_NAME, F_OK) != 0) {
|
||||
sprintf(folderName, "mkdir %s", DJI_LOG_FOLDER_NAME);
|
||||
ret = system(folderName);
|
||||
if (ret != 0) {
|
||||
printf("Create new log folder error, ret:%d.\r\n", ret);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
}
|
||||
|
||||
s_djiLogFileCnt = fopen(DJI_LOG_INDEX_FILE_NAME, "rb+");
|
||||
if (s_djiLogFileCnt == nullptr) {
|
||||
s_djiLogFileCnt = fopen(DJI_LOG_INDEX_FILE_NAME, "wb+");
|
||||
if (s_djiLogFileCnt == nullptr) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
} else {
|
||||
ret = fseek(s_djiLogFileCnt, 0, SEEK_SET);
|
||||
if (ret != 0) {
|
||||
printf("Seek log count file error, ret: %d, errno: %d.\r\n", ret, errno);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
ret = fread((uint16_t *) &logFileIndex, 1, sizeof(uint16_t), s_djiLogFileCnt);
|
||||
if (ret != sizeof(uint16_t)) {
|
||||
printf("Read log file index error.\r\n");
|
||||
}
|
||||
}
|
||||
|
||||
currentLogFileIndex = logFileIndex;
|
||||
logFileIndex++;
|
||||
|
||||
ret = fseek(s_djiLogFileCnt, 0, SEEK_SET);
|
||||
if (ret != 0) {
|
||||
printf("Seek log file error, ret: %d, errno: %d.\r\n", ret, errno);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
ret = fwrite((uint16_t *) &logFileIndex, 1, sizeof(uint16_t), s_djiLogFileCnt);
|
||||
if (ret != sizeof(uint16_t)) {
|
||||
printf("Write log file index error.\r\n");
|
||||
fclose(s_djiLogFileCnt);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
fclose(s_djiLogFileCnt);
|
||||
|
||||
sprintf(filePath, "%s_%04d_%04d%02d%02d_%02d-%02d-%02d.log", path, currentLogFileIndex,
|
||||
localTime->tm_year + 1900, localTime->tm_mon + 1, localTime->tm_mday,
|
||||
localTime->tm_hour, localTime->tm_min, localTime->tm_sec);
|
||||
|
||||
s_djiLogFile = fopen(filePath, "wb+");
|
||||
if (s_djiLogFile == nullptr) {
|
||||
USER_LOG_ERROR("Open filepath time error.");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
if (logFileIndex >= DJI_LOG_MAX_COUNT) {
|
||||
sprintf(systemCmd, "rm -rf %s_%04d*.log", path, currentLogFileIndex - DJI_LOG_MAX_COUNT);
|
||||
ret = system(systemCmd);
|
||||
if (ret != 0) {
|
||||
printf("Remove file error, ret:%d.\r\n", ret);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
}
|
||||
|
||||
return djiReturnCode;
|
||||
}
|
||||
|
||||
static void DjiUser_NormalExitHandler(int signalNum)
|
||||
{
|
||||
USER_UTIL_UNUSED(signalNum);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiTest_HighPowerApplyPinInit()
|
||||
{
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState)
|
||||
{
|
||||
//attention: please pull up the HWPR pin state by hardware.
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
@ -0,0 +1,67 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_application.hpp
|
||||
* @brief This is the header file for "dji_application.cpp", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef APPLICATION_H
|
||||
#define APPLICATION_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <iostream>
|
||||
#include <fstream>
|
||||
#include "dji_typedef.h"
|
||||
#include "dji_core.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
using namespace std;
|
||||
|
||||
class Application {
|
||||
public:
|
||||
Application(int argc, char **argv);
|
||||
~Application();
|
||||
|
||||
private:
|
||||
static void DjiUser_SetupEnvironment();
|
||||
static void DjiUser_ApplicationStart();
|
||||
static T_DjiReturnCode DjiUser_PrintConsole(const uint8_t *data, uint16_t dataLen);
|
||||
static T_DjiReturnCode DjiUser_LocalWrite(const uint8_t *data, uint16_t dataLen);
|
||||
static T_DjiReturnCode DjiUser_FillInUserInfo(T_DjiUserInfo *userInfo);
|
||||
static T_DjiReturnCode DjiUser_LocalWriteFsInit(const char *path);
|
||||
};
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // APPLICATION_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
@ -0,0 +1,55 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_sdk_app_info.h
|
||||
* @brief This is the header file for defining the structure and (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2018 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef DJI_SDK_APP_INFO_H
|
||||
#define DJI_SDK_APP_INFO_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
// ATTENTION: User must goto https://developer.dji.com/user/apps/#all to create your own dji sdk application, get dji sdk application
|
||||
// information then fill in the application information here.
|
||||
#define USER_APP_NAME "your_app_name"
|
||||
#define USER_APP_ID "your_app_id"
|
||||
#define USER_APP_KEY "your_app_key"
|
||||
#define USER_APP_LICENSE "your_app_license"
|
||||
#define USER_DEVELOPER_ACCOUNT "your_developer_account"
|
||||
#define USER_BAUD_RATE "460800"
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // DJI_SDK_APP_INFO_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
@ -0,0 +1,70 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file dji_sdk_config.h
|
||||
* @brief This is the header file for "dji_config.c", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef DJI_SDK_CONFIG_H
|
||||
#define DJI_SDK_CONFIG_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
#define DJI_USE_ONLY_UART (0)
|
||||
#define DJI_USE_UART_AND_USB_BULK_DEVICE (1)
|
||||
#define DJI_USE_UART_AND_NETWORK_DEVICE (2)
|
||||
#define DJI_USE_ONLY_USB_BULK_DEVICE (3)
|
||||
#define DJI_USE_ONLY_NETWORK_DEVICE (4)
|
||||
|
||||
/*!< Attention: Select your hardware connection mode here.
|
||||
* */
|
||||
#define CONFIG_HARDWARE_CONNECTION DJI_USE_ONLY_UART
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_CAMERA_EMU_ON true
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_CAMERA_MEDIA_ON true
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON true
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_WIDGET_ON true
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_WIDGET_SPEAKER_ON true
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_POWER_MANAGEMENT_ON true
|
||||
|
||||
#define CONFIG_MODULE_SAMPLE_DATA_TRANSMISSION_ON true
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // DJI_SDK_CONFIG_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
@ -0,0 +1,133 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file main.cpp
|
||||
* @brief
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <liveview/test_liveview_entry.hpp>
|
||||
#include <perception/test_perception_entry.hpp>
|
||||
#include <perception/test_lidar_entry.hpp>
|
||||
#include <perception/test_radar_entry.hpp>
|
||||
#include <flight_control/test_flight_control.h>
|
||||
#include <gimbal/test_gimbal_entry.hpp>
|
||||
#include "application.hpp"
|
||||
#include "fc_subscription/test_fc_subscription.h"
|
||||
#include <gimbal_emu/test_payload_gimbal_emu.h>
|
||||
#include <camera_emu/test_payload_cam_emu_media.h>
|
||||
#include <camera_emu/test_payload_cam_emu_base.h>
|
||||
#include <dji_logger.h>
|
||||
#include "widget/test_widget.h"
|
||||
#include "widget/test_widget_speaker.h"
|
||||
#include <power_management/test_power_management.h>
|
||||
#include "data_transmission/test_data_transmission.h"
|
||||
#include <flight_controller/test_flight_controller_entry.h>
|
||||
#include <positioning/test_positioning.h>
|
||||
#include <hms_manager/hms_manager_entry.h>
|
||||
#include "camera_manager/test_camera_manager_entry.h"
|
||||
#include <widget_manager/test_widget_manager.hpp>
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
int main(int argc, char **argv)
|
||||
{
|
||||
Application application(argc, argv);
|
||||
char inputChar;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiTestApplyHighPowerHandler applyHighPowerHandler;
|
||||
|
||||
start:
|
||||
std::cout
|
||||
<< "\n"
|
||||
<< "| Available commands: |\n"
|
||||
<< "| [0] Fc subscribe sample - subscribe quaternion and gps data |\n"
|
||||
<< "| [1] Flight controller sample - you can control flying by PSDK |\n"
|
||||
<< "| [2] Hms info manager sample - get health manger system info by language |\n"
|
||||
<< "| [a] Gimbal manager sample - you can control gimbal by PSDK |\n"
|
||||
<< "| [c] Camera stream view sample - display the camera video stream |\n"
|
||||
<< "| [d] Stereo vision view sample - display the stereo image |\n"
|
||||
<< "| [e] Run camera manager sample - you can test camera's functions interactively |\n"
|
||||
<< "| [f] Start rtk positioning sample - you can receive rtk rtcm data when rtk signal is ok |\n"
|
||||
<< "| [g] Request Lidar data sample - Request Lidar data and store the point cloud data as pcd files |\n"
|
||||
<< "| [h] Request Radar data sample - Request radar data |\n"
|
||||
<< "| [l] Run widget states manager sample, control widget states on other payload |\n"
|
||||
<< std::endl;
|
||||
|
||||
std::cin >> inputChar;
|
||||
switch (inputChar) {
|
||||
case '0':
|
||||
DjiTest_FcSubscriptionRunSample();
|
||||
break;
|
||||
case '1':
|
||||
DjiUser_RunFlightControllerSample();
|
||||
break;
|
||||
case '2':
|
||||
DjiUser_RunHmsManagerSample();
|
||||
break;
|
||||
case 'a':
|
||||
DjiUser_RunGimbalManagerSample();
|
||||
break;
|
||||
case 'c':
|
||||
DjiUser_RunCameraStreamViewSample();
|
||||
break;
|
||||
case 'd':
|
||||
DjiUser_RunStereoVisionViewSample();
|
||||
break;
|
||||
case 'e':
|
||||
DjiUser_RunCameraManagerSample();
|
||||
break;
|
||||
case 'f':
|
||||
returnCode = DjiTest_PositioningStartService();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("rtk positioning sample init error");
|
||||
break;
|
||||
}
|
||||
|
||||
USER_LOG_INFO("Start rtk positioning sample successfully");
|
||||
break;
|
||||
case 'g':
|
||||
DjiUser_RunLidarDataSubscriptionSample();
|
||||
break;
|
||||
case 'h':
|
||||
DjiUser_RunRadarDataSubscriptionSample();
|
||||
break;
|
||||
case 'l':
|
||||
DjiTest_WidgetMannagerStart();
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
osalHandler->TaskSleepMs(2000);
|
||||
|
||||
goto start;
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
176
samples/sample_c++/platform/linux/raspberry_pi/hal/hal_i2c.c
Normal file
176
samples/sample_c++/platform/linux/raspberry_pi/hal/hal_i2c.c
Normal file
@ -0,0 +1,176 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file hal_i2c.c
|
||||
* @brief
|
||||
*
|
||||
* @copyright (c) 2018 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "hal_i2c.h"
|
||||
#include <string.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <linux/i2c-dev.h>
|
||||
#include <linux/i2c.h>
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define I2C_DEVICE_RESET_TIME_US (25 * 1000)
|
||||
#define I2C_DEVICE_RESET_GPIO_NUM (4)
|
||||
#define DJI_SYSTEM_CMD_STR_MAX_SIZE (64)
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
typedef struct {
|
||||
int32_t i2cFd;
|
||||
} T_I2cHandleStruct;
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
static void HalI2c_ResetDevice(void);
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
T_DjiReturnCode HalI2c_Init(T_DjiHalI2cConfig i2cConfig, T_DjiI2cHandle *i2cHandle)
|
||||
{
|
||||
T_I2cHandleStruct *i2CHandleStruct = NULL;
|
||||
|
||||
//attention: suggest reset the i2c device before init it.
|
||||
HalI2c_ResetDevice();
|
||||
|
||||
i2CHandleStruct = malloc(sizeof(T_I2cHandleStruct));
|
||||
if (i2CHandleStruct == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_MEMORY_ALLOC_FAILED;
|
||||
}
|
||||
|
||||
i2CHandleStruct->i2cFd = open(LINUX_I2C_DEV1, O_RDWR);
|
||||
if (i2CHandleStruct->i2cFd < 0) {
|
||||
printf("Open i2c device failed, fd: %d\r\n", i2CHandleStruct->i2cFd);
|
||||
return -1;
|
||||
}
|
||||
|
||||
*i2cHandle = i2CHandleStruct;
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalI2c_DeInit(T_DjiI2cHandle i2cHandle)
|
||||
{
|
||||
T_I2cHandleStruct *i2CHandleStruct = (T_I2cHandleStruct *) i2cHandle;
|
||||
|
||||
close(i2CHandleStruct->i2cFd);
|
||||
free(i2CHandleStruct);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalI2c_WriteData(T_DjiI2cHandle i2cHandle, uint16_t devAddress, const uint8_t *buf,
|
||||
uint32_t len, uint32_t *realLen)
|
||||
{
|
||||
struct i2c_rdwr_ioctl_data data;
|
||||
struct i2c_msg messages;
|
||||
int32_t ret = 0;
|
||||
T_I2cHandleStruct *i2CHandleStruct = (T_I2cHandleStruct *) i2cHandle;
|
||||
|
||||
messages.addr = devAddress;
|
||||
messages.flags = 0;
|
||||
messages.len = len;
|
||||
messages.buf = (uint8_t *) buf;
|
||||
|
||||
data.msgs = &messages;
|
||||
data.nmsgs = 1;
|
||||
|
||||
ret = ioctl(i2CHandleStruct->i2cFd, I2C_RDWR, &data);
|
||||
if (ret < 0) {
|
||||
*realLen = 0;
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
*realLen = ret;
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalI2c_ReadData(T_DjiI2cHandle i2cHandle, uint16_t devAddress, uint8_t *buf,
|
||||
uint32_t len, uint32_t *realLen)
|
||||
{
|
||||
struct i2c_rdwr_ioctl_data data;
|
||||
struct i2c_msg messages;
|
||||
int32_t ret = 0;
|
||||
T_I2cHandleStruct *i2CHandleStruct = (T_I2cHandleStruct *) i2cHandle;
|
||||
|
||||
messages.addr = devAddress;
|
||||
messages.flags = I2C_M_RD;
|
||||
messages.len = len;
|
||||
messages.buf = buf;
|
||||
|
||||
data.msgs = &messages;
|
||||
data.nmsgs = 1;
|
||||
|
||||
ret = ioctl(i2CHandleStruct->i2cFd, I2C_RDWR, &data);
|
||||
if (ret < 0) {
|
||||
*realLen = 0;
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
*realLen = ret;
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
static void HalI2c_ResetDevice(void)
|
||||
{
|
||||
char systemCmd[DJI_SYSTEM_CMD_STR_MAX_SIZE] = {0};
|
||||
int32_t ret;
|
||||
|
||||
sprintf(systemCmd, "echo %d > /sys/class/gpio/export", I2C_DEVICE_RESET_GPIO_NUM);
|
||||
ret = system(systemCmd);
|
||||
if (ret != 0) {
|
||||
printf("Export reset gpio failed, %d\r\n", ret);
|
||||
}
|
||||
|
||||
sprintf(systemCmd, "echo out > /sys/class/gpio/gpio4/direction");
|
||||
ret = system(systemCmd);
|
||||
if (ret != 0) {
|
||||
printf("Set gpio direction failed, %d\r\n", ret);
|
||||
}
|
||||
|
||||
sprintf(systemCmd, "echo 0 > /sys/class/gpio/gpio4/value");
|
||||
ret = system(systemCmd);
|
||||
if (ret != 0) {
|
||||
printf("Set gpio value failed, %d\r\n", ret);
|
||||
}
|
||||
|
||||
usleep(I2C_DEVICE_RESET_TIME_US);
|
||||
|
||||
sprintf(systemCmd, "echo 1 > /sys/class/gpio/gpio4/value");
|
||||
ret = system(systemCmd);
|
||||
if (ret != 0) {
|
||||
printf("Set gpio value failed, %d\r\n", ret);
|
||||
}
|
||||
|
||||
sprintf(systemCmd, "echo %d > /sys/class/gpio/unexport", I2C_DEVICE_RESET_GPIO_NUM);
|
||||
ret = system(systemCmd);
|
||||
if (ret != 0) {
|
||||
printf("Unexport reset gpio failed, %d\r\n", ret);
|
||||
}
|
||||
}
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
55
samples/sample_c++/platform/linux/raspberry_pi/hal/hal_i2c.h
Normal file
55
samples/sample_c++/platform/linux/raspberry_pi/hal/hal_i2c.h
Normal file
@ -0,0 +1,55 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file hal_i2c.h
|
||||
* @brief This is the header file for "hal_i2c.c", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2018 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef HAL_I2C_H
|
||||
#define HAL_I2C_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_platform.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
#define LINUX_I2C_DEV1 "/dev/i2c-1"
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
T_DjiReturnCode HalI2c_Init(T_DjiHalI2cConfig i2cConfig, T_DjiI2cHandle *i2cHandle);
|
||||
T_DjiReturnCode HalI2c_DeInit(T_DjiI2cHandle i2cHandle);
|
||||
T_DjiReturnCode HalI2c_WriteData(T_DjiI2cHandle i2cHandle, uint16_t devAddress,
|
||||
const uint8_t *buf, uint32_t len, uint32_t *realLen);
|
||||
T_DjiReturnCode HalI2c_ReadData(T_DjiI2cHandle i2cHandle, uint16_t devAddress,
|
||||
uint8_t *buf, uint32_t len, uint32_t *realLen);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // HAL_I2C_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
@ -0,0 +1,92 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file hal_network.c
|
||||
* @version V2.0.0
|
||||
* @date 3/27/20
|
||||
* @brief
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "string.h"
|
||||
#include "stdlib.h"
|
||||
#include "stdio.h"
|
||||
#include "hal_network.h"
|
||||
#include "dji_logger.h"
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
T_DjiReturnCode HalNetWork_Init(const char *ipAddr, const char *netMask, T_DjiNetworkHandle *halObj)
|
||||
{
|
||||
int32_t ret;
|
||||
char cmdStr[LINUX_CMD_STR_MAX_SIZE];
|
||||
|
||||
if (ipAddr == NULL || netMask == NULL) {
|
||||
USER_LOG_ERROR("hal network config param error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
//Attention: need root permission to config ip addr and netmask.
|
||||
memset(cmdStr, 0, sizeof(cmdStr));
|
||||
|
||||
snprintf(cmdStr, sizeof(cmdStr), "ifconfig %s up", LINUX_NETWORK_DEV);
|
||||
ret = system(cmdStr);
|
||||
if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Can't open the network."
|
||||
"Probably the program not execute with root permission."
|
||||
"Please use the root permission to execute the program.");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
snprintf(cmdStr, sizeof(cmdStr), "ifconfig %s %s netmask %s", LINUX_NETWORK_DEV, ipAddr, netMask);
|
||||
ret = system(cmdStr);
|
||||
if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Can't config the ip address of network."
|
||||
"Probably the program not execute with root permission."
|
||||
"Please use the root permission to execute the program.");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalNetWork_DeInit(T_DjiNetworkHandle halObj)
|
||||
{
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalNetWork_GetDeviceInfo(T_DjiHalNetworkDeviceInfo *deviceInfo)
|
||||
{
|
||||
deviceInfo->usbNetAdapter.vid = USB_NET_ADAPTER_VID;
|
||||
deviceInfo->usbNetAdapter.pid = USB_NET_ADAPTER_PID;
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
@ -0,0 +1,73 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file hal_network.h
|
||||
* @brief This is the header file for "hal_network.c", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef HAL_NETWORK_H
|
||||
#define HAL_NETWORK_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_platform.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/** @attention User can config network card name here, if your device is not MF2C/G, please comment below and add your
|
||||
* NIC name micro define as #define 'LINUX_NETWORK_DEV "your NIC name"'.
|
||||
*/
|
||||
#ifdef PLATFORM_ARCH_x86_64
|
||||
#define LINUX_NETWORK_DEV "enp0s31f6"
|
||||
#else
|
||||
#define LINUX_NETWORK_DEV "pi4br0"
|
||||
#endif
|
||||
/**
|
||||
* @attention
|
||||
*/
|
||||
|
||||
#ifdef PLATFORM_ARCH_x86_64
|
||||
#define USB_NET_ADAPTER_VID (0x0B95)
|
||||
#define USB_NET_ADAPTER_PID (0x1790)
|
||||
#else
|
||||
#define USB_NET_ADAPTER_VID (0x0955)
|
||||
#define USB_NET_ADAPTER_PID (0x7020)
|
||||
#endif
|
||||
|
||||
#define LINUX_CMD_STR_MAX_SIZE (128)
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
T_DjiReturnCode HalNetWork_Init(const char *ipAddr, const char *netMask, T_DjiNetworkHandle *halObj);
|
||||
T_DjiReturnCode HalNetWork_DeInit(T_DjiNetworkHandle halObj);
|
||||
T_DjiReturnCode HalNetWork_GetDeviceInfo(T_DjiHalNetworkDeviceInfo *deviceInfo);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // HAL_NETWORK_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
272
samples/sample_c++/platform/linux/raspberry_pi/hal/hal_uart.c
Normal file
272
samples/sample_c++/platform/linux/raspberry_pi/hal/hal_uart.c
Normal file
@ -0,0 +1,272 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file hal_uart.c
|
||||
* @brief
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <dji_logger.h>
|
||||
#include "hal_uart.h"
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define UART_DEV_NAME_STR_SIZE (128)
|
||||
#define DJI_SYSTEM_CMD_STR_MAX_SIZE (64)
|
||||
#define DJI_SYSTEM_RESULT_STR_MAX_SIZE (128)
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
typedef struct {
|
||||
int uartFd;
|
||||
} T_UartHandleStruct;
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
T_DjiReturnCode HalUart_Init(E_DjiHalUartNum uartNum, uint32_t baudRate, T_DjiUartHandle *uartHandle)
|
||||
{
|
||||
T_UartHandleStruct *uartHandleStruct;
|
||||
struct termios options;
|
||||
struct flock lock;
|
||||
T_DjiReturnCode returnCode = DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
char uartName[UART_DEV_NAME_STR_SIZE];
|
||||
char systemCmd[DJI_SYSTEM_CMD_STR_MAX_SIZE];
|
||||
char *ret = NULL;
|
||||
char lineBuf[DJI_SYSTEM_RESULT_STR_MAX_SIZE] = {0};
|
||||
FILE *fp;
|
||||
|
||||
uartHandleStruct = malloc(sizeof(T_UartHandleStruct));
|
||||
if (uartHandleStruct == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_MEMORY_ALLOC_FAILED;
|
||||
}
|
||||
|
||||
if (uartNum == DJI_HAL_UART_NUM_0) {
|
||||
strcpy(uartName, LINUX_UART_DEV1);
|
||||
} else if (uartNum == DJI_HAL_UART_NUM_1) {
|
||||
strcpy(uartName, LINUX_UART_DEV2);
|
||||
} else {
|
||||
goto free_uart_handle;
|
||||
}
|
||||
|
||||
#ifdef USE_CLION_DEBUG
|
||||
sprintf(systemCmd, "ls -l %s", uartName);
|
||||
fp = popen(systemCmd, "r");
|
||||
if (fp == NULL) {
|
||||
goto free_uart_handle;
|
||||
}
|
||||
|
||||
ret = fgets(lineBuf, sizeof(lineBuf), fp);
|
||||
if (ret == NULL) {
|
||||
goto close_fp;
|
||||
}
|
||||
|
||||
if (strstr(lineBuf, "crwxrwxrwx") == NULL) {
|
||||
USER_LOG_ERROR("Can't operation the device. "
|
||||
"Probably the device has not operation permission. "
|
||||
"Please execute command 'sudo chmod 777 %s' to add permission. ", uartName);
|
||||
goto close_fp;
|
||||
}
|
||||
#else
|
||||
sprintf(systemCmd, "chmod 777 %s", uartName);
|
||||
fp = popen(systemCmd, "r");
|
||||
if (fp == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
#endif
|
||||
|
||||
uartHandleStruct->uartFd = open(uartName, (unsigned) O_RDWR | (unsigned) O_NOCTTY | (unsigned) O_NDELAY);
|
||||
if (uartHandleStruct->uartFd == -1) {
|
||||
goto close_fp;
|
||||
}
|
||||
|
||||
// Forbid multiple psdk programs to access the serial port
|
||||
lock.l_type = F_WRLCK;
|
||||
lock.l_pid = getpid();
|
||||
lock.l_whence = SEEK_SET;
|
||||
lock.l_start = 0;
|
||||
lock.l_len = 0;
|
||||
|
||||
if (fcntl(uartHandleStruct->uartFd, F_GETLK, &lock) < 0) {
|
||||
goto close_uart_fd;
|
||||
}
|
||||
if (lock.l_type != F_UNLCK) {
|
||||
goto close_uart_fd;
|
||||
}
|
||||
lock.l_type = F_WRLCK;
|
||||
lock.l_pid = getpid();
|
||||
lock.l_whence = SEEK_SET;
|
||||
lock.l_start = 0;
|
||||
lock.l_len = 0;
|
||||
if (fcntl(uartHandleStruct->uartFd, F_SETLKW, &lock) < 0) {
|
||||
goto close_uart_fd;
|
||||
}
|
||||
|
||||
if (tcgetattr(uartHandleStruct->uartFd, &options) != 0) {
|
||||
goto close_uart_fd;
|
||||
}
|
||||
|
||||
switch (baudRate) {
|
||||
case 115200:
|
||||
cfsetispeed(&options, B115200);
|
||||
cfsetospeed(&options, B115200);
|
||||
break;
|
||||
case 230400:
|
||||
cfsetispeed(&options, B230400);
|
||||
cfsetospeed(&options, B230400);
|
||||
break;
|
||||
case 460800:
|
||||
cfsetispeed(&options, B460800);
|
||||
cfsetospeed(&options, B460800);
|
||||
break;
|
||||
case 921600:
|
||||
cfsetispeed(&options, B921600);
|
||||
cfsetospeed(&options, B921600);
|
||||
break;
|
||||
case 1000000:
|
||||
cfsetispeed(&options, B1000000);
|
||||
cfsetospeed(&options, B1000000);
|
||||
break;
|
||||
default:
|
||||
goto close_uart_fd;
|
||||
}
|
||||
|
||||
options.c_cflag |= (unsigned) CLOCAL;
|
||||
options.c_cflag |= (unsigned) CREAD;
|
||||
options.c_cflag &= ~(unsigned) CRTSCTS;
|
||||
options.c_cflag &= ~(unsigned) CSIZE;
|
||||
options.c_cflag |= (unsigned) CS8;
|
||||
options.c_cflag &= ~(unsigned) PARENB;
|
||||
options.c_iflag &= ~(unsigned) INPCK;
|
||||
options.c_cflag &= ~(unsigned) CSTOPB;
|
||||
options.c_oflag &= ~(unsigned) OPOST;
|
||||
options.c_lflag &= ~((unsigned) ICANON | (unsigned) ECHO | (unsigned) ECHOE | (unsigned) ISIG);
|
||||
options.c_iflag &= ~((unsigned) BRKINT | (unsigned) ICRNL | (unsigned) INPCK | (unsigned) ISTRIP | (unsigned) IXON);
|
||||
options.c_cc[VTIME] = 0;
|
||||
options.c_cc[VMIN] = 0;
|
||||
|
||||
tcflush(uartHandleStruct->uartFd, TCIFLUSH);
|
||||
|
||||
if (tcsetattr(uartHandleStruct->uartFd, TCSANOW, &options) != 0) {
|
||||
goto close_uart_fd;
|
||||
}
|
||||
|
||||
*uartHandle = uartHandleStruct;
|
||||
pclose(fp);
|
||||
|
||||
return returnCode;
|
||||
|
||||
close_uart_fd:
|
||||
close(uartHandleStruct->uartFd);
|
||||
|
||||
close_fp:
|
||||
pclose(fp);
|
||||
|
||||
free_uart_handle:
|
||||
free(uartHandleStruct);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUart_DeInit(T_DjiUartHandle uartHandle)
|
||||
{
|
||||
int32_t ret;
|
||||
T_UartHandleStruct *uartHandleStruct = (T_UartHandleStruct *) uartHandle;
|
||||
|
||||
if (uartHandle == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
}
|
||||
|
||||
ret = close(uartHandleStruct->uartFd);
|
||||
if (ret < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
free(uartHandleStruct);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf, uint32_t len, uint32_t *realLen)
|
||||
{
|
||||
int32_t ret;
|
||||
T_UartHandleStruct *uartHandleStruct = (T_UartHandleStruct *) uartHandle;
|
||||
|
||||
if (uartHandle == NULL || buf == NULL || len == 0 || realLen == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
ret = write(uartHandleStruct->uartFd, buf, len);
|
||||
if (ret >= 0) {
|
||||
*realLen = ret;
|
||||
} else {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen)
|
||||
{
|
||||
int32_t ret;
|
||||
T_UartHandleStruct *uartHandleStruct = (T_UartHandleStruct *) uartHandle;
|
||||
|
||||
if (uartHandle == NULL || buf == NULL || len == 0 || realLen == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
ret = read(uartHandleStruct->uartFd, buf, len);
|
||||
if (ret >= 0) {
|
||||
*realLen = ret;
|
||||
} else {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *status)
|
||||
{
|
||||
if (uartNum == DJI_HAL_UART_NUM_0) {
|
||||
status->isConnect = true;
|
||||
} else if (uartNum == DJI_HAL_UART_NUM_1) {
|
||||
status->isConnect = true;
|
||||
} else {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo)
|
||||
{
|
||||
if (deviceInfo == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
deviceInfo->vid = USB_UART_CONNECTED_TO_UAV_VID;
|
||||
deviceInfo->pid = USB_UART_CONNECTED_TO_UAV_PID;
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
@ -0,0 +1,75 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file hal_uart.h
|
||||
* @brief This is the header file for "hal_uart.c", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef HAL_UART_H
|
||||
#define HAL_UART_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "stdint.h"
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <termios.h>
|
||||
#include <unistd.h>
|
||||
#include <string.h>
|
||||
#include "stdlib.h"
|
||||
|
||||
#include "dji_platform.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
//User can config dev based on there environmental conditions
|
||||
#define LINUX_UART_DEV1 "/dev/ttyAMA1"
|
||||
#define LINUX_UART_DEV2 "/dev/ttyAMA2"
|
||||
|
||||
/**
|
||||
* Use for Eport 2.0, specify the VID and PID of the USB serial port closest to the aircraft.
|
||||
* FT232 0x0403:0x6001
|
||||
* CP2102 0x10C4:0xEA60
|
||||
* VCOM 0x2CA3:0xF002
|
||||
*/
|
||||
#define USB_UART_CONNECTED_TO_UAV_VID (0x0403)
|
||||
#define USB_UART_CONNECTED_TO_UAV_PID (0x6001)
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
T_DjiReturnCode HalUart_Init(E_DjiHalUartNum uartNum, uint32_t baudRate, T_DjiUartHandle *uartHandle);
|
||||
T_DjiReturnCode HalUart_DeInit(T_DjiUartHandle uartHandle);
|
||||
T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf, uint32_t len, uint32_t *realLen);
|
||||
T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen);
|
||||
T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *status);
|
||||
T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // HAL_UART_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
@ -0,0 +1,253 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file hal_usb_bulk.c
|
||||
* @brief
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "hal_usb_bulk.h"
|
||||
#include "dji_logger.h"
|
||||
#include <errno.h>
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define LINUX_USB_BULK_TRANSFER_TIMEOUT_MS (50)
|
||||
#define LINUX_USB_BULK_TRANSFER_WAIT_FOREVER (-1)
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
typedef struct {
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
libusb_device_handle *handle;
|
||||
#else
|
||||
void *handle;
|
||||
#endif
|
||||
int32_t ep1;
|
||||
int32_t ep2;
|
||||
uint32_t interfaceNum;
|
||||
T_DjiHalUsbBulkInfo usbBulkInfo;
|
||||
} T_HalUsbBulkObj;
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHandle *usbBulkHandle)
|
||||
{
|
||||
int32_t ret;
|
||||
struct libusb_device_handle *handle = NULL;
|
||||
|
||||
*usbBulkHandle = malloc(sizeof(T_HalUsbBulkObj));
|
||||
if (*usbBulkHandle == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
if (usbBulkInfo.isUsbHost == true) {
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
ret = libusb_init(NULL);
|
||||
if (ret < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
handle = libusb_open_device_with_vid_pid(NULL, usbBulkInfo.vid, usbBulkInfo.pid);
|
||||
if (handle == NULL) {
|
||||
USER_LOG_ERROR("libusb open device error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
ret = libusb_claim_interface(handle, usbBulkInfo.channelInfo.interfaceNum);
|
||||
if (ret != LIBUSB_SUCCESS) {
|
||||
USER_LOG_ERROR("libusb claim interface error");
|
||||
libusb_close(handle);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle;
|
||||
memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo));
|
||||
#endif
|
||||
} else {
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->handle = handle;
|
||||
memcpy(&((T_HalUsbBulkObj *) *usbBulkHandle)->usbBulkInfo, &usbBulkInfo, sizeof(usbBulkInfo));
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->interfaceNum = usbBulkInfo.channelInfo.interfaceNum;
|
||||
|
||||
if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK1_INTERFACE_NUM) {
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK1_EP_IN_FD, O_RDWR);
|
||||
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK1_EP_OUT_FD, O_RDWR);
|
||||
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
} else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK2_INTERFACE_NUM) {
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK2_EP_IN_FD, O_RDWR);
|
||||
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK2_EP_OUT_FD, O_RDWR);
|
||||
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
} else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK3_INTERFACE_NUM) {
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK3_EP_IN_FD, O_RDWR);
|
||||
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK3_EP_OUT_FD, O_RDWR);
|
||||
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle)
|
||||
{
|
||||
struct libusb_device_handle *handle = NULL;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
|
||||
if (usbBulkHandle == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
||||
|
||||
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
libusb_release_interface(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum);
|
||||
osalHandler->TaskSleepMs(100);
|
||||
libusb_exit(NULL);
|
||||
#endif
|
||||
} else {
|
||||
close(((T_HalUsbBulkObj *) usbBulkHandle)->ep1);
|
||||
close(((T_HalUsbBulkObj *) usbBulkHandle)->ep2);
|
||||
}
|
||||
|
||||
free(usbBulkHandle);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUsbBulk_WriteData(T_DjiUsbBulkHandle usbBulkHandle, const uint8_t *buf, uint32_t len,
|
||||
uint32_t *realLen)
|
||||
{
|
||||
int32_t ret;
|
||||
int32_t actualLen;
|
||||
struct libusb_device_handle *handle = NULL;
|
||||
|
||||
if (usbBulkHandle == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
||||
|
||||
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointOut,
|
||||
(uint8_t *) buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_TIMEOUT_MS);
|
||||
if (ret < 0) {
|
||||
USER_LOG_ERROR("Write usb bulk data failed, errno = %d", ret);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
*realLen = actualLen;
|
||||
#endif
|
||||
} else {
|
||||
ret = write(((T_HalUsbBulkObj *) usbBulkHandle)->ep1, buf, len);
|
||||
if (ret < 0) {
|
||||
USER_LOG_ERROR("write ret %d %d %s\n", ret, errno, strerror(errno));
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
} else {
|
||||
*realLen = ret;
|
||||
}
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len,
|
||||
uint32_t *realLen)
|
||||
{
|
||||
int32_t ret;
|
||||
struct libusb_device_handle *handle = NULL;
|
||||
int32_t actualLen;
|
||||
|
||||
if (usbBulkHandle == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
handle = ((T_HalUsbBulkObj *) usbBulkHandle)->handle;
|
||||
|
||||
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
ret = libusb_bulk_transfer(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.endPointIn,
|
||||
buf, len, &actualLen, LINUX_USB_BULK_TRANSFER_WAIT_FOREVER);
|
||||
if (ret < 0) {
|
||||
USER_LOG_ERROR("Read usb bulk data failed, errno = %d", ret);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
*realLen = actualLen;
|
||||
#endif
|
||||
} else {
|
||||
ret = read(((T_HalUsbBulkObj *) usbBulkHandle)->ep2, buf, len);
|
||||
if (ret < 0) {
|
||||
USER_LOG_ERROR("read ret %d %d %s\n", ret, errno, strerror(errno));
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
} else {
|
||||
*realLen = ret;
|
||||
}
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo)
|
||||
{
|
||||
//attention: this interface only be called in usb device mode.
|
||||
deviceInfo->vid = LINUX_USB_VID;
|
||||
deviceInfo->pid = LINUX_USB_PID;
|
||||
|
||||
// This bulk channel is used to obtain DJI camera video stream and push 3rd-party camera video stream.
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].interfaceNum = LINUX_USB_BULK1_INTERFACE_NUM;
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].endPointIn = LINUX_USB_BULK1_END_POINT_IN;
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].endPointOut = LINUX_USB_BULK1_END_POINT_OUT;
|
||||
|
||||
// This bulk channel is used to obtain DJI perception image and download camera media file.
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].interfaceNum = LINUX_USB_BULK2_INTERFACE_NUM;
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointIn = LINUX_USB_BULK2_END_POINT_IN;
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointOut = LINUX_USB_BULK2_END_POINT_OUT;
|
||||
|
||||
// This bulk channel is used to obtain DJI perception data.
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].interfaceNum = LINUX_USB_BULK3_INTERFACE_NUM;
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointIn = LINUX_USB_BULK3_END_POINT_IN;
|
||||
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_2].endPointOut = LINUX_USB_BULK3_END_POINT_OUT;
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
@ -0,0 +1,95 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file hal_usb_bulk.h
|
||||
* @brief This is the header file for "hal_usb_bulk.c", defining the structure and
|
||||
* (exported) function prototypes.
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef HAL_USB_BULK_H
|
||||
#define HAL_USB_BULK_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "stdint.h"
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <termios.h>
|
||||
#include <unistd.h>
|
||||
#include <string.h>
|
||||
#include <sys/socket.h>
|
||||
#include <netinet/in.h>
|
||||
#include <arpa/inet.h>
|
||||
|
||||
#ifdef LIBUSB_INSTALLED
|
||||
|
||||
#include <libusb-1.0/libusb.h>
|
||||
|
||||
#endif
|
||||
|
||||
#include "dji_platform.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
#define LINUX_USB_BULK1_EP_IN_FD "/dev/usb-ffs/bulk1/ep1"
|
||||
#define LINUX_USB_BULK1_EP_OUT_FD "/dev/usb-ffs/bulk1/ep2"
|
||||
|
||||
#define LINUX_USB_BULK1_INTERFACE_NUM (0)
|
||||
#define LINUX_USB_BULK1_END_POINT_IN (0x81)
|
||||
#define LINUX_USB_BULK1_END_POINT_OUT (0x01)
|
||||
|
||||
#define LINUX_USB_BULK2_EP_IN_FD "/dev/usb-ffs/bulk2/ep1"
|
||||
#define LINUX_USB_BULK2_EP_OUT_FD "/dev/usb-ffs/bulk2/ep2"
|
||||
|
||||
#define LINUX_USB_BULK2_INTERFACE_NUM (1)
|
||||
#define LINUX_USB_BULK2_END_POINT_IN (0x82)
|
||||
#define LINUX_USB_BULK2_END_POINT_OUT (0x02)
|
||||
|
||||
#define LINUX_USB_BULK3_EP_IN_FD "/dev/usb-ffs/bulk3/ep1"
|
||||
#define LINUX_USB_BULK3_EP_OUT_FD "/dev/usb-ffs/bulk3/ep2"
|
||||
|
||||
#define LINUX_USB_BULK3_INTERFACE_NUM (2)
|
||||
#define LINUX_USB_BULK3_END_POINT_IN (0x83)
|
||||
#define LINUX_USB_BULK3_END_POINT_OUT (0x03)
|
||||
|
||||
#define LINUX_USB_VID (0x2CA3)
|
||||
#define LINUX_USB_PID (0xF001)
|
||||
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHandle *usbBulkHandle);
|
||||
T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle);
|
||||
T_DjiReturnCode HalUsbBulk_WriteData(T_DjiUsbBulkHandle usbBulkHandle, const uint8_t *buf, uint32_t len,
|
||||
uint32_t *realLen);
|
||||
T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *buf, uint32_t len, uint32_t *realLen);
|
||||
T_DjiReturnCode HalUsbBulk_GetDeviceInfo(T_DjiHalUsbBulkDeviceInfo *deviceInfo);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // HAL_USB_BULK_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
@ -33,6 +33,7 @@
|
||||
#include "dji_gimbal.h"
|
||||
#include "dji_xport.h"
|
||||
#include "gimbal_emu/test_payload_gimbal_emu.h"
|
||||
#include <widget_interaction_test/test_widget_interaction.h>
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define PAYLOAD_CAMERA_EMU_TASK_FREQ (100)
|
||||
@ -118,6 +119,7 @@ static T_TestCameraGimbalRotationArgument s_tapZoomNewestGimbalRotationArgument
|
||||
static uint32_t s_tapZoomNewestTargetHybridFocalLength = 0; // unit: 0.1mm
|
||||
static T_DjiMutexHandle s_tapZoomMutex = NULL;
|
||||
static E_DjiCameraVideoStreamType s_cameraVideoStreamType;
|
||||
static uint32_t s_currentVideoRecordTimeInSeconds = 0;
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
static T_DjiReturnCode GetSystemState(T_DjiCameraSystemState *systemState);
|
||||
@ -205,6 +207,7 @@ static T_DjiReturnCode SetMode(E_DjiCameraMode mode)
|
||||
|
||||
s_cameraState.cameraMode = mode;
|
||||
USER_LOG_INFO("set camera mode:%d", mode);
|
||||
DjiTest_WidgetLogAppend("set cam mode %d", mode);
|
||||
|
||||
returnCode = osalHandler->MutexUnlock(s_commonMutex);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -235,6 +238,7 @@ static T_DjiReturnCode StartRecordVideo(void)
|
||||
|
||||
s_cameraState.isRecording = true;
|
||||
USER_LOG_INFO("start record video");
|
||||
DjiTest_WidgetLogAppend("start record video");
|
||||
|
||||
out:
|
||||
djiStat = osalHandler->MutexUnlock(s_commonMutex);
|
||||
@ -267,6 +271,7 @@ static T_DjiReturnCode StopRecordVideo(void)
|
||||
s_cameraState.isRecording = false;
|
||||
s_cameraState.currentVideoRecordingTimeInSeconds = 0;
|
||||
USER_LOG_INFO("stop record video");
|
||||
DjiTest_WidgetLogAppend("stop record video");
|
||||
|
||||
out:
|
||||
djiStat = osalHandler->MutexUnlock(s_commonMutex);
|
||||
@ -290,6 +295,7 @@ static T_DjiReturnCode StartShootPhoto(void)
|
||||
}
|
||||
|
||||
USER_LOG_INFO("start shoot photo");
|
||||
DjiTest_WidgetLogAppend("start shoot photo");
|
||||
s_cameraState.isStoring = true;
|
||||
|
||||
if (s_cameraShootPhotoMode == DJI_CAMERA_SHOOT_PHOTO_MODE_SINGLE) {
|
||||
@ -300,6 +306,7 @@ static T_DjiReturnCode StartShootPhoto(void)
|
||||
s_cameraState.shootingState = DJI_CAMERA_SHOOTING_INTERVAL_PHOTO;
|
||||
s_cameraState.isShootingIntervalStart = true;
|
||||
s_cameraState.currentPhotoShootingIntervalTimeInSeconds = s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds;
|
||||
s_cameraState.currentPhotoShootingIntervalTimeInMs = s_cameraPhotoTimeIntervalSettings.timeIntervalMilliseconds;
|
||||
}
|
||||
|
||||
returnCode = osalHandler->MutexUnlock(s_commonMutex);
|
||||
@ -323,6 +330,7 @@ static T_DjiReturnCode StopShootPhoto(void)
|
||||
}
|
||||
|
||||
USER_LOG_INFO("stop shoot photo");
|
||||
DjiTest_WidgetLogAppend("stop shoot photo");
|
||||
s_cameraState.shootingState = DJI_CAMERA_SHOOTING_PHOTO_IDLE;
|
||||
s_cameraState.isStoring = false;
|
||||
s_cameraState.isShootingIntervalStart = false;
|
||||
@ -439,8 +447,9 @@ static T_DjiReturnCode SetPhotoTimeIntervalSettings(T_DjiCameraPhotoTimeInterval
|
||||
|
||||
s_cameraPhotoTimeIntervalSettings.captureCount = settings.captureCount;
|
||||
s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds = settings.timeIntervalSeconds;
|
||||
USER_LOG_INFO("set photo interval settings count:%d seconds:%d", settings.captureCount,
|
||||
settings.timeIntervalSeconds);
|
||||
s_cameraPhotoTimeIntervalSettings.timeIntervalMilliseconds = settings.timeIntervalMilliseconds;
|
||||
USER_LOG_INFO("set photo interval settings count:%d seconds:%d.%d", settings.captureCount,
|
||||
settings.timeIntervalSeconds, settings.timeIntervalMilliseconds / 100);
|
||||
s_cameraState.currentPhotoShootingIntervalCount = settings.captureCount;
|
||||
|
||||
returnCode = osalHandler->MutexUnlock(s_commonMutex);
|
||||
@ -907,7 +916,17 @@ static T_DjiReturnCode DjiTest_CameraRotationGimbal(T_TestCameraGimbalRotationAr
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
if (aircraftBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_XPORT) {
|
||||
if (aircraftBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 ||
|
||||
aircraftBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V3 ||
|
||||
aircraftBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE ||
|
||||
aircraftBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_NONE) {
|
||||
returnCode = DjiTest_GimbalRotate(gimbalRotationArgument.rotationMode, gimbalRotationArgument.rotationProperty,
|
||||
gimbalRotationArgument.rotationValue);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("rotate gimbal error: 0x%08llX.", returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
} else if (aircraftBaseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_XPORT) {
|
||||
returnCode = DjiXPort_RotateSync(gimbalRotationArgument.rotationMode, gimbalRotationArgument.rotationProperty,
|
||||
gimbalRotationArgument.rotationValue);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -938,6 +957,7 @@ static void *UserCamera_Task(void *arg)
|
||||
uint32_t currentTime = 0;
|
||||
bool isStartIntervalPhotoAction = false;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
uint32_t intervalFreq = 10;
|
||||
|
||||
USER_UTIL_UNUSED(arg);
|
||||
|
||||
@ -1130,8 +1150,7 @@ out:
|
||||
}
|
||||
}
|
||||
|
||||
// 1Hz
|
||||
if (USER_UTIL_IS_WORK_TURN(step, 1, PAYLOAD_CAMERA_EMU_TASK_FREQ)) {
|
||||
if (USER_UTIL_IS_WORK_TURN(step, intervalFreq, PAYLOAD_CAMERA_EMU_TASK_FREQ)) {
|
||||
returnCode = osalHandler->MutexLock(s_commonMutex);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("lock mutex error: 0x%08llX.", returnCode);
|
||||
@ -1139,13 +1158,21 @@ out:
|
||||
}
|
||||
|
||||
if (s_cameraState.isRecording) {
|
||||
s_cameraState.currentVideoRecordingTimeInSeconds++;
|
||||
s_cameraSDCardState.remainSpaceInMB =
|
||||
s_cameraSDCardState.remainSpaceInMB - SDCARD_PER_SECONDS_RECORD_SPACE_IN_MB;
|
||||
if (s_cameraSDCardState.remainSpaceInMB > SDCARD_TOTAL_SPACE_IN_MB) {
|
||||
s_cameraSDCardState.remainSpaceInMB = 0;
|
||||
s_cameraSDCardState.isFull = true;
|
||||
uint16_t preTimeInSeconds = s_cameraState.currentVideoRecordingTimeInSeconds;
|
||||
|
||||
s_currentVideoRecordTimeInSeconds++;
|
||||
|
||||
s_cameraState.currentVideoRecordingTimeInSeconds = s_currentVideoRecordTimeInSeconds / intervalFreq;
|
||||
if (s_cameraState.currentVideoRecordingTimeInSeconds > preTimeInSeconds) {
|
||||
s_cameraSDCardState.remainSpaceInMB =
|
||||
s_cameraSDCardState.remainSpaceInMB - SDCARD_PER_SECONDS_RECORD_SPACE_IN_MB;
|
||||
if (s_cameraSDCardState.remainSpaceInMB > SDCARD_TOTAL_SPACE_IN_MB) {
|
||||
s_cameraSDCardState.remainSpaceInMB = 0;
|
||||
s_cameraSDCardState.isFull = true;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
s_currentVideoRecordTimeInSeconds = 0;
|
||||
}
|
||||
|
||||
if (s_cameraState.isShootingIntervalStart == false) {
|
||||
@ -1154,10 +1181,16 @@ out:
|
||||
|
||||
if (s_cameraShootPhotoMode == DJI_CAMERA_SHOOT_PHOTO_MODE_INTERVAL
|
||||
&& s_cameraState.isShootingIntervalStart == true && s_cameraPhotoTimeIntervalSettings.captureCount > 0
|
||||
&& s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds > 0) {
|
||||
s_cameraState.currentPhotoShootingIntervalTimeInSeconds--;
|
||||
&& (s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds > 0 || s_cameraPhotoTimeIntervalSettings.timeIntervalMilliseconds > 0)) {
|
||||
uint16_t currentPhotoShootingIntervalTimeInMs = s_cameraState.currentPhotoShootingIntervalTimeInSeconds * 1000 +
|
||||
s_cameraState.currentPhotoShootingIntervalTimeInMs;
|
||||
|
||||
if ((s_cameraState.currentPhotoShootingIntervalTimeInSeconds == 0 &&
|
||||
currentPhotoShootingIntervalTimeInMs -= 1000 / intervalFreq;
|
||||
|
||||
s_cameraState.currentPhotoShootingIntervalTimeInSeconds = currentPhotoShootingIntervalTimeInMs / 1000;
|
||||
s_cameraState.currentPhotoShootingIntervalTimeInMs = currentPhotoShootingIntervalTimeInMs % 1000;
|
||||
|
||||
if ((currentPhotoShootingIntervalTimeInMs == 0 &&
|
||||
s_cameraState.currentPhotoShootingIntervalCount > 0) ||
|
||||
(s_cameraState.isShootingIntervalStart == true && isStartIntervalPhotoAction == false)) {
|
||||
|
||||
@ -1165,13 +1198,14 @@ out:
|
||||
|
||||
s_cameraState.shootingState = DJI_CAMERA_SHOOTING_INTERVAL_PHOTO;
|
||||
s_cameraState.isStoring = true;
|
||||
s_cameraState.currentPhotoShootingIntervalTimeInSeconds
|
||||
= s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds;
|
||||
s_cameraState.currentPhotoShootingIntervalTimeInSeconds = s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds;
|
||||
s_cameraState.currentPhotoShootingIntervalTimeInMs = s_cameraPhotoTimeIntervalSettings.timeIntervalMilliseconds;
|
||||
if (s_cameraState.currentPhotoShootingIntervalCount < INTERVAL_PHOTOGRAPH_ALWAYS_COUNT) {
|
||||
USER_LOG_INFO("interval taking photograph count:%d interval_time:%ds",
|
||||
USER_LOG_INFO("interval taking photograph count:%d interval_time:%d.%ds",
|
||||
(s_cameraPhotoTimeIntervalSettings.captureCount -
|
||||
s_cameraState.currentPhotoShootingIntervalCount + 1),
|
||||
s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds);
|
||||
s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds,
|
||||
s_cameraPhotoTimeIntervalSettings.timeIntervalMilliseconds / 100);
|
||||
s_cameraState.currentPhotoShootingIntervalCount--;
|
||||
if (s_cameraState.currentPhotoShootingIntervalCount == 0) {
|
||||
s_cameraState.shootingState = DJI_CAMERA_SHOOTING_PHOTO_IDLE;
|
||||
@ -1179,8 +1213,9 @@ out:
|
||||
s_cameraState.isShootingIntervalStart = false;
|
||||
}
|
||||
} else {
|
||||
USER_LOG_INFO("interval taking photograph always, interval_time:%ds",
|
||||
s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds);
|
||||
USER_LOG_INFO("interval taking photograph always, interval_time:%d.%ds",
|
||||
s_cameraPhotoTimeIntervalSettings.timeIntervalSeconds,
|
||||
s_cameraPhotoTimeIntervalSettings.timeIntervalMilliseconds / 100);
|
||||
s_cameraState.currentPhotoShootingIntervalCount--;
|
||||
}
|
||||
}
|
||||
|
||||
@ -194,7 +194,8 @@ T_DjiReturnCode DjiTest_CameraEmuMediaStartService(void)
|
||||
UtilBuffer_Init(&s_mediaPlayCommandBufferHandler, s_mediaPlayCommandBuffer, sizeof(s_mediaPlayCommandBuffer));
|
||||
|
||||
if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M300_RTK ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK) {
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M350_RTK ||
|
||||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M400) {
|
||||
returnCode = DjiPayloadCamera_RegMediaDownloadPlaybackHandler(&s_psdkCameraMedia);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("psdk camera media function init error.");
|
||||
|
||||
@ -855,6 +855,8 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition,
|
||||
|| DJI_CAMERA_TYPE_M30 == cameraType || DJI_CAMERA_TYPE_M30T == cameraType
|
||||
|| DJI_CAMERA_TYPE_M3E == cameraType || DJI_CAMERA_TYPE_M3T == cameraType
|
||||
|| DJI_CAMERA_TYPE_M3D == cameraType || DJI_CAMERA_TYPE_M3TD == cameraType
|
||||
|| DJI_CAMERA_TYPE_M4T == cameraType || DJI_CAMERA_TYPE_M4TD == cameraType
|
||||
|| DJI_CAMERA_TYPE_H30 == cameraType || DJI_CAMERA_TYPE_H30T == cameraType
|
||||
|| DJI_CAMERA_TYPE_M4T == cameraType || DJI_CAMERA_TYPE_M4E == cameraType
|
||||
|| DJI_CAMERA_TYPE_H30 == cameraType || DJI_CAMERA_TYPE_H30T == cameraType
|
||||
|| DJI_CAMERA_TYPE_M4TD == cameraType || DJI_CAMERA_TYPE_M4D == cameraType
|
||||
@ -899,9 +901,10 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition,
|
||||
|| DJI_CAMERA_TYPE_M30 == cameraType || DJI_CAMERA_TYPE_M30T == cameraType
|
||||
|| DJI_CAMERA_TYPE_M3E == cameraType || DJI_CAMERA_TYPE_M3T == cameraType
|
||||
|| DJI_CAMERA_TYPE_M3D == cameraType || DJI_CAMERA_TYPE_M3TD == cameraType
|
||||
|| DJI_CAMERA_TYPE_M4T == cameraType || DJI_CAMERA_TYPE_M4E == cameraType
|
||||
|| DJI_CAMERA_TYPE_H30 == cameraType || DJI_CAMERA_TYPE_H30T == cameraType
|
||||
|| DJI_CAMERA_TYPE_M4TD == cameraType || DJI_CAMERA_TYPE_M4D == cameraType
|
||||
|| DJI_CAMERA_TYPE_M4T == cameraType || DJI_CAMERA_TYPE_M4TD == cameraType
|
||||
|| DJI_CAMERA_TYPE_M4E == cameraType || DJI_CAMERA_TYPE_H30 == cameraType
|
||||
|| DJI_CAMERA_TYPE_H30T == cameraType|| DJI_CAMERA_TYPE_M4TD == cameraType
|
||||
|| DJI_CAMERA_TYPE_M4D == cameraType
|
||||
) {
|
||||
USER_LOG_INFO("Set mounted position %d camera's exposure mode to manual mode.",
|
||||
mountPosition);
|
||||
@ -1938,7 +1941,8 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition,
|
||||
cameraType == DJI_CAMERA_TYPE_L1 || cameraType == DJI_CAMERA_TYPE_M30 ||
|
||||
cameraType == DJI_CAMERA_TYPE_M3E || cameraType == DJI_CAMERA_TYPE_M3D ||
|
||||
cameraType == DJI_CAMERA_TYPE_L2 || cameraType == DJI_CAMERA_TYPE_H30 ||
|
||||
cameraType == DJI_CAMERA_TYPE_M4T || cameraType == DJI_CAMERA_TYPE_M4TD) {
|
||||
cameraType == DJI_CAMERA_TYPE_M4TD || cameraType == DJI_CAMERA_TYPE_M4D ||
|
||||
cameraType == DJI_CAMERA_TYPE_M4T) {
|
||||
USER_LOG_WARN("Camera type %s don't support FFC function.",
|
||||
s_cameraTypeStrList[DjiTest_CameraManagerGetCameraTypeIndex(cameraType)].cameraTypeStr);
|
||||
goto exitCameraModule;
|
||||
@ -1985,7 +1989,8 @@ T_DjiReturnCode DjiTest_CameraManagerRunSample(E_DjiMountPosition mountPosition,
|
||||
cameraType == DJI_CAMERA_TYPE_L1 || cameraType == DJI_CAMERA_TYPE_M30 ||
|
||||
cameraType == DJI_CAMERA_TYPE_M3E || cameraType == DJI_CAMERA_TYPE_M3D ||
|
||||
cameraType == DJI_CAMERA_TYPE_L2 || cameraType == DJI_CAMERA_TYPE_H30 ||
|
||||
cameraType == DJI_CAMERA_TYPE_M4T || cameraType == DJI_CAMERA_TYPE_M4TD) {
|
||||
cameraType == DJI_CAMERA_TYPE_M4TD || cameraType == DJI_CAMERA_TYPE_M4D ||
|
||||
cameraType == DJI_CAMERA_TYPE_M4T) {
|
||||
USER_LOG_WARN("Camera type %s don't support infrared function.",
|
||||
s_cameraTypeStrList[DjiTest_CameraManagerGetCameraTypeIndex(cameraType)].cameraTypeStr);
|
||||
goto exitCameraModule;
|
||||
@ -2133,6 +2138,7 @@ static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_Dj
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
USER_LOG_INFO("obtain downloader rights of pos %d", position);
|
||||
returnCode = DjiCameraManager_ObtainDownloaderRights(position);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Obtain downloader rights failed, error code: 0x%08X.", returnCode);
|
||||
@ -2215,10 +2221,10 @@ static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_Dj
|
||||
}
|
||||
|
||||
if (s_meidaFileList.fileListInfo[0].type == DJI_CAMERA_FILE_TYPE_JPEG) {
|
||||
USER_LOG_INFO("delete camera file of index %d", s_meidaFileList.fileListInfo[0].fileIndex);
|
||||
returnCode = DjiCameraManager_DeleteFileByIndex(position, s_meidaFileList.fileListInfo[0].fileIndex);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Delete media file by index failed, error code: 0x%08X.", returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
}
|
||||
|
||||
@ -2227,6 +2233,7 @@ static T_DjiReturnCode DjiTest_CameraManagerMediaDownloadAndDeleteMediaFile(E_Dj
|
||||
USER_LOG_WARN("Media file is not existed in sdcard.\r\n");
|
||||
}
|
||||
|
||||
ReleaseDownloaderRights:
|
||||
returnCode = DjiCameraManager_ReleaseDownloaderRights(position);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Release downloader rights failed, error code: 0x%08X.", returnCode);
|
||||
@ -2575,6 +2582,7 @@ T_DjiReturnCode DjiTest_CameraManagerSubscribePointCloud(E_DjiMountPosition posi
|
||||
uint32_t colorPointCloudDataByte = 0;
|
||||
uint32_t colorPointsNum = 0;
|
||||
static bool isMopInit = false;
|
||||
E_DjiChannelAddress mopChannelAddress = 0;
|
||||
|
||||
returnCode = DjiCameraManager_StartRecordPointCloud(position);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -2613,7 +2621,10 @@ T_DjiReturnCode DjiTest_CameraManagerSubscribePointCloud(E_DjiMountPosition posi
|
||||
|
||||
RECONNECT:
|
||||
osalHandler->TaskSleepMs(TEST_CAMERA_MOP_CHANNEL_WAIT_TIME_MS);
|
||||
returnCode = DjiMopChannel_Connect(s_mopChannelHandle, DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO1,
|
||||
mopChannelAddress = position - DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1 + DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO1;
|
||||
USER_LOG_INFO("connect to mop channel addr %d, channel id %d",
|
||||
mopChannelAddress, TEST_CAMERA_MOP_CHANNEL_SUBSCRIBE_POINT_CLOUD_CHANNEL_ID);
|
||||
returnCode = DjiMopChannel_Connect(s_mopChannelHandle, mopChannelAddress,
|
||||
TEST_CAMERA_MOP_CHANNEL_SUBSCRIBE_POINT_CLOUD_CHANNEL_ID);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Connect point cloud mop channel error, stat:0x%08llX.", returnCode);
|
||||
|
||||
@ -0,0 +1,99 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file test_cloud_api_by_web_socket.c
|
||||
* @brief
|
||||
*
|
||||
* @copyright (c) 2021 DJI. All rights reserved.
|
||||
*
|
||||
* All information contained herein is, and remains, the property of DJI.
|
||||
* The intellectual and technical concepts contained herein are proprietary
|
||||
* to DJI and may be covered by U.S. and foreign patents, patents in process,
|
||||
* and protected by trade secret or copyright law. Dissemination of this
|
||||
* information, including but not limited to data and other proprietary
|
||||
* material(s) incorporated within the information, in any form, is strictly
|
||||
* prohibited without the express written consent of DJI.
|
||||
*
|
||||
* If you receive this source code without DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
|
||||
#include <utils/util_misc.h>
|
||||
#include <stdio.h>
|
||||
#include <utils/util_md5.h>
|
||||
#include "dji_cloud_api_by_websockt.h"
|
||||
#include "dji_logger.h"
|
||||
#include "dji_platform.h"
|
||||
#include "test_cloud_api_by_web_socket.h"
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define TEST_MOP_CHANNEL_NORMAL_TRANSFOR_SEND_BUFFER (64 * 1024)
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
|
||||
/* Private values -------------------------------------------------------------*/
|
||||
|
||||
/* Private functions declaration ---------------------------------------------*/
|
||||
static T_DjiTaskHandle s_testCloudApiByWebSocketSendTask;
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wmissing-noreturn"
|
||||
#pragma GCC diagnostic ignored "-Wreturn-type"
|
||||
|
||||
static void *DjiTest_CloudApiByWebSocketSendTask(void *arg)
|
||||
{
|
||||
uint8_t *sendBuf = NULL;
|
||||
uint32_t realLen = 0;
|
||||
T_DjiReturnCode returnCode;
|
||||
uint32_t sendDataCount = 0;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
|
||||
USER_UTIL_UNUSED(arg);
|
||||
|
||||
sendBuf = osalHandler->Malloc(TEST_MOP_CHANNEL_NORMAL_TRANSFOR_SEND_BUFFER);
|
||||
if (sendBuf == NULL) {
|
||||
USER_LOG_ERROR("cloud_api over mop malloc send buffer error");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
while (1) {
|
||||
sendDataCount++;
|
||||
memset(sendBuf, 'A' - 1 + (sendDataCount % 26), TEST_MOP_CHANNEL_NORMAL_TRANSFOR_SEND_BUFFER);
|
||||
returnCode = DjiCloudApi_SendDataByWebSocket(sendBuf, TEST_MOP_CHANNEL_NORMAL_TRANSFOR_SEND_BUFFER, &realLen);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_WARN("cloud_api over mop send data to channel error,stat:0x%08llX", returnCode);
|
||||
} else {
|
||||
USER_LOG_INFO("cloud_api over mop send data to channel length:%d count:%d", realLen, sendDataCount);
|
||||
}
|
||||
|
||||
osalHandler->TaskSleepMs(1000);
|
||||
}
|
||||
}
|
||||
|
||||
#pragma GCC diagnostic pop
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
T_DjiReturnCode DjiTest_CloudApiByWebSocketStartService(void)
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
|
||||
USER_LOG_INFO("cloud_api over mop send task create error, stat:0x%08llX.", returnCode);
|
||||
returnCode = osalHandler->TaskCreate("CloudApiByWebSocket", DjiTest_CloudApiByWebSocketSendTask,
|
||||
2048, NULL, &s_testCloudApiByWebSocketSendTask);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("cloud_api over mop send task create error, stat:0x%08llX.", returnCode);
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
@ -0,0 +1,49 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @file test_mop_channel.h
|
||||
* @brief This is the header file for "test_mop_channel.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 TEST_CLOUD_API_BY_WEEBSOCKET_H
|
||||
#define TEST_CLOUD_API_BY_WEEBSOCKET_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "dji_typedef.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
T_DjiReturnCode DjiTest_CloudApiByWebSocketStartService(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // TEST_CLOUD_API_BY_WEEBSOCKET_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
@ -87,7 +87,7 @@ T_DjiReturnCode DjiTest_DataTransmissionStartService(void)
|
||||
s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30T ||
|
||||
s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3D ||
|
||||
s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3TD ||
|
||||
s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M4D ||
|
||||
s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M4D ||
|
||||
s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M4TD) {
|
||||
channelAddress = DJI_CHANNEL_ADDRESS_CLOUD_API;
|
||||
djiStat = DjiLowSpeedDataChannel_RegRecvDataCallback(channelAddress, ReceiveDataFromCloud);
|
||||
@ -97,7 +97,10 @@ T_DjiReturnCode DjiTest_DataTransmissionStartService(void)
|
||||
}
|
||||
}
|
||||
|
||||
if (s_aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1 ||
|
||||
if (s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M400) {
|
||||
USER_LOG_INFO("M400 is not support to use data transmition between PSDK device.");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
} else if (s_aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1 ||
|
||||
s_aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_PAYLOAD_PORT_NO2 ||
|
||||
s_aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_PAYLOAD_PORT_NO3) {
|
||||
channelAddress = DJI_CHANNEL_ADDRESS_EXTENSION_PORT;
|
||||
|
||||
@ -99,6 +99,7 @@ static void DjiTest_FlightControlVelocityControlSample(void);
|
||||
static void DjiTest_FlightControlArrestFlyingSample(void);
|
||||
static void DjiTest_FlightControlSetGetParamSample(void);
|
||||
static void DjiTest_FlightControlPassiveTriggerFtsSample(void);
|
||||
static void DjiTest_FlightControlSlowRotateMotorSample(void);
|
||||
static T_DjiReturnCode DjiTest_TriggerFtsEventCallback(void);
|
||||
static void DjiTest_FlightControlSample(E_DjiTestFlightCtrlSampleSelect flightCtrlSampleSelect);
|
||||
|
||||
@ -922,6 +923,63 @@ void DjiTest_FlightControlPassiveTriggerFtsSample(void)
|
||||
}
|
||||
}
|
||||
|
||||
static void DjiTest_FlightControlSlowRotateMotorSample(void)
|
||||
{
|
||||
E_DjiFlightControllerElectronicSpeedControllerStatus escStatus;
|
||||
|
||||
T_DjiReturnCode returnCode = 0;
|
||||
|
||||
USER_LOG_INFO("Start rotating.");
|
||||
returnCode = DjiFlightController_StartSlowRotateMotor();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Start slow rotate blade failed, error code is 0x%08X", returnCode);
|
||||
return ;
|
||||
}
|
||||
|
||||
returnCode = DjiFlightController_GetElectronicSpeedControllerStatus(&escStatus);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Fail to get ESC status, error code is 0x%08X", returnCode);
|
||||
}
|
||||
|
||||
USER_LOG_INFO("The ESC status is: %s motor(s) in rotate mode",
|
||||
escStatus == DJI_FLIGHT_CONTROLLER_NO_MOTOR_IN_SLOW_ROTATE_MODE ? "no" :
|
||||
escStatus == DJI_FLIGHT_CONTROLLER_SOME_MOTOR_IN_SLOW_ROTATE_MODE ? "some" :
|
||||
escStatus == DJI_FLIGHT_CONTROLLER_ALL_MOTOR_IN_SLOW_ROTATE_MODE ? "all" : "(error)");
|
||||
|
||||
for (int32_t i = 0; i < 8; i++) {
|
||||
s_osalHandler->TaskSleepMs(1000);
|
||||
|
||||
returnCode = DjiFlightController_GetElectronicSpeedControllerStatus(&escStatus);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Fail to get ESC status, error code is 0x%08X", returnCode);
|
||||
}
|
||||
|
||||
USER_LOG_INFO("The ESC status is: %s motor(s) in rotate mode",
|
||||
escStatus == DJI_FLIGHT_CONTROLLER_NO_MOTOR_IN_SLOW_ROTATE_MODE ? "no" :
|
||||
escStatus == DJI_FLIGHT_CONTROLLER_SOME_MOTOR_IN_SLOW_ROTATE_MODE ? "some" :
|
||||
escStatus == DJI_FLIGHT_CONTROLLER_ALL_MOTOR_IN_SLOW_ROTATE_MODE ? "all" : "(error)");
|
||||
}
|
||||
|
||||
USER_LOG_INFO("Stop rotating.");
|
||||
returnCode = DjiFlightController_StopSlowRotateMotor();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_INFO("Stop slow rotate blade failed, error code is 0x%08X", returnCode);
|
||||
return ;
|
||||
}
|
||||
|
||||
s_osalHandler->TaskSleepMs(1000);
|
||||
|
||||
returnCode = DjiFlightController_GetElectronicSpeedControllerStatus(&escStatus);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Fail to get ESC status, error code is 0x%08X", returnCode);
|
||||
}
|
||||
|
||||
USER_LOG_INFO("The ESC status is: %s motor(s) in rotate mode",
|
||||
escStatus == DJI_FLIGHT_CONTROLLER_NO_MOTOR_IN_SLOW_ROTATE_MODE ? "no" :
|
||||
escStatus == DJI_FLIGHT_CONTROLLER_SOME_MOTOR_IN_SLOW_ROTATE_MODE ? "some" :
|
||||
escStatus == DJI_FLIGHT_CONTROLLER_ALL_MOTOR_IN_SLOW_ROTATE_MODE ? "all" : "(error)");
|
||||
}
|
||||
|
||||
void DjiTest_FlightControlSample(E_DjiTestFlightCtrlSampleSelect flightCtrlSampleSelect)
|
||||
{
|
||||
switch (flightCtrlSampleSelect) {
|
||||
@ -953,6 +1011,10 @@ void DjiTest_FlightControlSample(E_DjiTestFlightCtrlSampleSelect flightCtrlSampl
|
||||
DjiTest_FlightControlPassiveTriggerFtsSample();
|
||||
break;
|
||||
}
|
||||
case E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SLOW_ROTATE_BLADE: {
|
||||
DjiTest_FlightControlSlowRotateMotorSample();
|
||||
break;
|
||||
}
|
||||
default:
|
||||
break;
|
||||
}
|
||||
@ -1305,6 +1367,8 @@ bool DjiTest_FlightControlGoHomeAndConfirmLanding(void)
|
||||
if (DJI_AIRCRAFT_TYPE_M3E == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M3T == aircraftInfoBaseInfo.aircraftType
|
||||
|| DJI_AIRCRAFT_TYPE_M3D == aircraftInfoBaseInfo.aircraftType || DJI_AIRCRAFT_TYPE_M3TD == aircraftInfoBaseInfo.aircraftType
|
||||
|| DJI_AIRCRAFT_TYPE_M4T == aircraftInfoBaseInfo.aircraftType
|
||||
|| DJI_AIRCRAFT_TYPE_M4TD == aircraftInfoBaseInfo.aircraftType
|
||||
|| DJI_AIRCRAFT_TYPE_M4D == aircraftInfoBaseInfo.aircraftType
|
||||
|| DJI_AIRCRAFT_TYPE_M4E == aircraftInfoBaseInfo.aircraftType
|
||||
|| DJI_AIRCRAFT_TYPE_M4TD == aircraftInfoBaseInfo.aircraftType
|
||||
|| DJI_AIRCRAFT_TYPE_M4D == aircraftInfoBaseInfo.aircraftType
|
||||
@ -1608,4 +1672,62 @@ DjiTest_FlightControlJoystickCtrlAuthSwitchEventCallback(T_DjiFlightControllerJo
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
static T_DjiReturnCode DjiTest_FlightControlSetFtsTrigger(E_DjiMountPosition position, char* desc)
|
||||
{
|
||||
T_DjiReturnCode djiStat;
|
||||
T_DjiFtsPwmEscTriggerStatus esc_status;
|
||||
|
||||
djiStat = DjiFlightController_SelectFtsPwmTrigger(position);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("select fts pwm trigger E-PORT error, error code: 0x%08X", djiStat);
|
||||
return djiStat;
|
||||
}
|
||||
|
||||
djiStat = DjiFlightController_GetFtsPwmTriggerStatus(&esc_status);
|
||||
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("get pwm trigger status error, error code: 0x%08X", djiStat);
|
||||
return djiStat;
|
||||
}
|
||||
|
||||
if (esc_status.ESC[0].fts_select != position || esc_status.ESC[1].fts_select != position)
|
||||
{
|
||||
USER_LOG_ERROR("pwm trigger status incorrect");
|
||||
return djiStat;
|
||||
}
|
||||
|
||||
if (esc_status.ESC[0].fts_status == DJI_FLIGHT_CONTROLLER_FTS_NOT_TRIGGERD && esc_status.ESC[1].fts_status == DJI_FLIGHT_CONTROLLER_FTS_NOT_TRIGGERD)
|
||||
|
||||
USER_LOG_INFO("Set fts trigger position %s success", desc);
|
||||
|
||||
return djiStat;
|
||||
}
|
||||
|
||||
T_DjiReturnCode DjiTest_FlightControlFtsPwmTriggerSample(void)
|
||||
{
|
||||
T_DjiReturnCode returnCode;
|
||||
|
||||
returnCode = DjiTest_FlightControlInit();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Init flight Control sample failed,error code:0x%08llX", returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
returnCode = DjiTest_FlightControlSetFtsTrigger(DJI_MOUNT_POSITION_EXTENSION_PORT, "DJI_MOUNT_POSITION_EXTENSION_PORT");
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Test select DJI_MOUNT_POSITION_EXTENSION_PORT fts pwm trigger failed");
|
||||
return returnCode;
|
||||
}
|
||||
returnCode = DjiTest_FlightControlSetFtsTrigger(DJI_MOUNT_POSITION_EXTENSION_LITE_PORT, "DJI_MOUNT_POSITION_EXTENSION_LITE_PORT");
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Test select DJI_MOUNT_POSITION_EXTENSION_LITE_PORT fts pwm trigger failed");
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
returnCode = DjiTest_FlightControlDeInit();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Deinit Flight Control sample failed,error code:0x%08llX", returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
|
||||
@ -43,6 +43,7 @@ typedef enum {
|
||||
E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_ARREST_FLYING,
|
||||
E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SET_GET_PARAM,
|
||||
E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_FTS_TRIGGER,
|
||||
E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SLOW_ROTATE_BLADE,
|
||||
} E_DjiTestFlightCtrlSampleSelect;
|
||||
|
||||
#pragma pack(1)
|
||||
@ -59,6 +60,7 @@ typedef struct {
|
||||
T_DjiReturnCode DjiTest_FlightControlRunSample(E_DjiTestFlightCtrlSampleSelect flightCtrlSampleSelect);
|
||||
void DjiTest_FlightControlVelocityAndYawRateCtrl(const T_DjiTestFlightControlVector3f offsetDesired, float yawRate,
|
||||
uint32_t timeMs);
|
||||
T_DjiReturnCode DjiTest_FlightControlFtsPwmTriggerSample(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
||||
@ -30,6 +30,7 @@
|
||||
#include "dji_logger.h"
|
||||
#include "dji_platform.h"
|
||||
#include "utils/util_misc.h"
|
||||
#include "widget_interaction_test/test_widget_interaction.h"
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define PAYLOAD_GIMBAL_EMU_TASK_STACK_SIZE (2048)
|
||||
@ -277,6 +278,7 @@ T_DjiReturnCode DjiTest_GimbalRotate(E_DjiGimbalRotationMode rotationMode,
|
||||
|
||||
break;
|
||||
case DJI_GIMBAL_ROTATION_MODE_ABSOLUTE_ANGLE:
|
||||
DjiTest_WidgetLogAppend("abs mode (%d %d %d)", rotationValue.pitch, rotationValue.roll, rotationValue.yaw);
|
||||
USER_LOG_INFO("gimbal absolute rotate angle: pitch %d, roll %d, yaw %d.", rotationValue.pitch,
|
||||
rotationValue.roll, rotationValue.yaw);
|
||||
USER_LOG_DEBUG("gimbal absolute rotate action time: %d.",
|
||||
@ -325,6 +327,7 @@ T_DjiReturnCode DjiTest_GimbalRotate(E_DjiGimbalRotationMode rotationMode,
|
||||
|
||||
break;
|
||||
case DJI_GIMBAL_ROTATION_MODE_SPEED:
|
||||
DjiTest_WidgetLogAppend("speed mode (%d %d %d)", rotationValue.pitch, rotationValue.roll, rotationValue.yaw);
|
||||
USER_LOG_INFO("gimbal rotate speed: pitch %d, roll %d, yaw %d.", rotationValue.pitch,
|
||||
rotationValue.roll, rotationValue.yaw);
|
||||
|
||||
|
||||
@ -77,6 +77,7 @@ T_DjiReturnCode DjiTest_GimbalManagerRunSample(E_DjiMountPosition mountPosition,
|
||||
T_DjiGimbalManagerRotation rotation;
|
||||
T_DjiAircraftInfoBaseInfo baseInfo;
|
||||
E_DjiAircraftSeries aircraftSeries;
|
||||
bool gimbalAnglesSubscribedFlag = false;
|
||||
|
||||
returnCode = DjiAircraftInfo_GetBaseInfo(&baseInfo);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -89,10 +90,17 @@ T_DjiReturnCode DjiTest_GimbalManagerRunSample(E_DjiMountPosition mountPosition,
|
||||
USER_LOG_INFO("Gimbal manager sample start");
|
||||
DjiTest_WidgetLogAppend("Gimbal manager sample start");
|
||||
|
||||
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("Failed to subscribe topic %d, 0x%08X", DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, returnCode);
|
||||
goto out;
|
||||
if (DJI_AIRCRAFT_SERIES_M30 == aircraftSeries ||
|
||||
DJI_AIRCRAFT_SERIES_M3 == aircraftSeries ||
|
||||
DJI_AIRCRAFT_SERIES_M3D == aircraftSeries ||
|
||||
DJI_AIRCRAFT_SERIES_M4 == aircraftSeries ||
|
||||
DJI_AIRCRAFT_SERIES_M4D == aircraftSeries) {
|
||||
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("Failed to subscribe topic %d, 0x%08X", DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, returnCode);
|
||||
goto out;
|
||||
}
|
||||
gimbalAnglesSubscribedFlag = true;
|
||||
}
|
||||
|
||||
USER_LOG_INFO("--> Step 1: Init gimbal manager module");
|
||||
@ -170,9 +178,12 @@ T_DjiReturnCode DjiTest_GimbalManagerRunSample(E_DjiMountPosition mountPosition,
|
||||
}
|
||||
}
|
||||
|
||||
returnCode = DjiFcSubscription_UnSubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Failed to unsubscribe topic %d, 0x%08X", DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, returnCode);
|
||||
if (gimbalAnglesSubscribedFlag) {
|
||||
returnCode = DjiFcSubscription_UnSubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Failed to unsubscribe topic %d, 0x%08X", DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, returnCode);
|
||||
}
|
||||
gimbalAnglesSubscribedFlag = false;
|
||||
}
|
||||
|
||||
USER_LOG_INFO("--> Step 5: Deinit gimbal manager module");
|
||||
|
||||
@ -43,7 +43,11 @@
|
||||
#define MAX_HMS_ERROR_LEVEL (6)
|
||||
#define HMS_DIR_PATH_LEN_MAX (256)
|
||||
|
||||
#ifdef SYSTEM_ARCH_LINUX
|
||||
#define DJI_CUSTOM_HMS_CODE_INJECT_ON (0)
|
||||
#else
|
||||
#define DJI_CUSTOM_HMS_CODE_INJECT_ON (1)
|
||||
#endif
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
|
||||
|
||||
@ -28,6 +28,7 @@
|
||||
#include "dji_logger.h"
|
||||
#include "dji_flight_controller.h"
|
||||
#include "flight_control/test_flight_control.h"
|
||||
#include "dji_aircraft_info.h"
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
|
||||
@ -45,11 +46,18 @@ T_DjiReturnCode DjiTest_InterestPointRunSample(void)
|
||||
T_DjiInterestPointSettings interestPointSettings = {0};
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
T_DjiFlightControllerRidInfo ridInfo = {0};
|
||||
T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo = {0};
|
||||
|
||||
ridInfo.latitude = 22.542812;
|
||||
ridInfo.longitude = 113.958902;
|
||||
ridInfo.altitude = 10;
|
||||
|
||||
returnCode = DjiAircraftInfo_GetBaseInfo(&aircraftInfoBaseInfo);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("get aircraft base info error");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
returnCode = DjiFlightController_Init(ridInfo);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Flight control init failed, errno=%lld", returnCode);
|
||||
@ -74,8 +82,8 @@ T_DjiReturnCode DjiTest_InterestPointRunSample(void)
|
||||
osalHandler->TaskSleepMs(1000);
|
||||
DjiTest_FlightControlVelocityAndYawRateCtrl((T_DjiTestFlightControlVector3f) {3, 0, 0}, 0, 5000);
|
||||
|
||||
interestPointSettings.latitude = 22.542812;
|
||||
interestPointSettings.longitude = 113.958902;
|
||||
interestPointSettings.latitude = 22.57775;
|
||||
interestPointSettings.longitude = 113.94265;
|
||||
|
||||
returnCode = DjiInterestPoint_RegMissionStateCallback(DjiUser_InterestPointMissionStateCallback);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -83,25 +91,37 @@ T_DjiReturnCode DjiTest_InterestPointRunSample(void)
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
if (aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M400) {
|
||||
interestPointSettings.payloadCameraIndex = 1;
|
||||
USER_LOG_INFO("The sample try to use payload camera on position %d for poi, please make sure that DJI camera mounted on this position.",
|
||||
interestPointSettings.payloadCameraIndex);
|
||||
}
|
||||
|
||||
USER_LOG_INFO("Start interest point circle, circumcenter(%f, %f)", interestPointSettings.latitude, interestPointSettings.longitude);
|
||||
returnCode = DjiInterestPoint_Start(interestPointSettings);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Point interest start failed, errno=%lld", returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
DjiInterestPoint_SetSpeed(5.0f);
|
||||
osalHandler->TaskSleepMs(1000);
|
||||
|
||||
USER_LOG_INFO("set speed to 15");
|
||||
DjiInterestPoint_SetSpeed(15.0f);
|
||||
|
||||
for (int i = 0; i < 60; ++i) {
|
||||
USER_LOG_INFO("Interest point mission running %d.", i);
|
||||
osalHandler->TaskSleepMs(1000);
|
||||
}
|
||||
|
||||
USER_LOG_INFO("Stop interest point circle");
|
||||
returnCode = DjiInterestPoint_Stop();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("Point interest stop failed, errno=%lld", returnCode);
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
USER_LOG_INFO("Force landing");
|
||||
DjiFlightController_StartForceLanding();
|
||||
|
||||
returnCode = DjiInterestPoint_DeInit();
|
||||
@ -122,7 +142,11 @@ T_DjiReturnCode DjiTest_InterestPointRunSample(void)
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
static T_DjiReturnCode DjiUser_InterestPointMissionStateCallback(T_DjiInterestPointMissionState missionState)
|
||||
{
|
||||
USER_LOG_INFO("Interest point state: %d, radius: %.2f m, speed: %.2f m/s", missionState.state, missionState.radius,
|
||||
USER_LOG_INFO("Interest point state: %s, radius: %.2f m, speed: %.2f m/s",
|
||||
missionState.state == DJI_INTEREST_POINT_MISSION_ACTION_STATE_NOT_STARTED ? "not started" :
|
||||
missionState.state == DJI_INTEREST_POINT_MISSION_ACTION_STATE_PAUSE ? "pause" :
|
||||
missionState.state == DJI_INTEREST_POINT_MISSION_ACTION_STATE_RUNNING ? "running" : "unknown",
|
||||
missionState.radius,
|
||||
missionState.curSpeed);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
|
||||
@ -77,12 +77,13 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition)
|
||||
goto out;
|
||||
}
|
||||
|
||||
USER_LOG_INFO("--> Step 2: Start h264 stream of the fpv and selected payload\r\n");
|
||||
USER_LOG_INFO("--> Step 2: Start h264 stream of the fpv and default of selected payload\r\n");
|
||||
DjiTest_WidgetLogAppend("--> Step 2: Start h264 stream of the fpv and selected payload\r\n");
|
||||
|
||||
if (aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M300 ||
|
||||
aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M350 ||
|
||||
aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M30) {
|
||||
aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M30 ||
|
||||
aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M400) {
|
||||
|
||||
localTime = localtime(¤tTime);
|
||||
sprintf(s_fpvCameraStreamFilePath, "fpv_stream_%04d%02d%02d_%02d-%02d-%02d.h264",
|
||||
@ -98,7 +99,7 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition)
|
||||
}
|
||||
|
||||
localTime = localtime(¤tTime);
|
||||
sprintf(s_payloadCameraStreamFilePath, "payload%d_vis_stream_%04d%02d%02d_%02d-%02d-%02d.h264",
|
||||
sprintf(s_payloadCameraStreamFilePath, "payload%d_default_stream_%04d%02d%02d_%02d-%02d-%02d.h264",
|
||||
mountPosition, localTime->tm_year + 1900, localTime->tm_mon + 1, localTime->tm_mday,
|
||||
localTime->tm_hour, localTime->tm_min, localTime->tm_sec);
|
||||
|
||||
@ -128,7 +129,8 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition)
|
||||
DjiTest_WidgetLogAppend("--> Step 3: Stop h264 stream of the fpv and selected payload");
|
||||
if (aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M300 ||
|
||||
aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M350 ||
|
||||
aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M30) {
|
||||
aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M30 ||
|
||||
aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M400) {
|
||||
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);
|
||||
@ -143,9 +145,6 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition)
|
||||
goto out;
|
||||
}
|
||||
|
||||
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 (DJI_AIRCRAFT_TYPE_M3T == aircraftInfoBaseInfo.aircraftType
|
||||
|| DJI_AIRCRAFT_TYPE_M3TD == aircraftInfoBaseInfo.aircraftType
|
||||
|| DJI_AIRCRAFT_TYPE_M4T == aircraftInfoBaseInfo.aircraftType
|
||||
|
||||
@ -723,6 +723,8 @@ static void *DjiTest_MopChannelFileServiceRecvTask(void *arg)
|
||||
s_fileServiceContent[clientNum].uploadState = MOP_FILE_SERVICE_UPLOAD_DATA_SENDING;
|
||||
s_fileServiceContent[clientNum].uploadSeqNum = fileTransfor->seqNum;
|
||||
|
||||
USER_LOG_INFO("fileTransfor->seqNum %d", fileTransfor->seqNum);
|
||||
|
||||
uploadWriteLen = fwrite(&recvBuf[UTIL_OFFSETOF(T_DjiMopChannel_FileTransfor, data)], 1,
|
||||
fileTransfor->dataLen, uploadFile);
|
||||
if (uploadWriteLen < 0) {
|
||||
|
||||
@ -39,11 +39,11 @@
|
||||
#endif
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define POSITIONING_TASK_FREQ (1)
|
||||
#define POSITIONING_TASK_STACK_SIZE (2048)
|
||||
#define POSITIONING_TASK_FREQ (0.1)
|
||||
#define POSITIONING_TASK_STACK_SIZE (3 * 1024)
|
||||
#define TEST_RTCM_FILE_PATH_STR_MAX_SIZE (64)
|
||||
|
||||
#define DJI_TEST_POSITIONING_EVENT_COUNT (2)
|
||||
#define DJI_TEST_POSITIONING_EVENT_COUNT (1)
|
||||
#define DJI_TEST_TIME_INTERVAL_AMONG_EVENTS_US (200000)
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
@ -168,22 +168,22 @@ static void *DjiTest_PositioningTask(void *arg)
|
||||
continue;
|
||||
}
|
||||
|
||||
USER_LOG_DEBUG("request position of target points success.");
|
||||
USER_LOG_DEBUG("detail position information:");
|
||||
USER_LOG_INFO("request position of target points success.");
|
||||
USER_LOG_INFO("detail position information:");
|
||||
for (i = 0; i < DJI_TEST_POSITIONING_EVENT_COUNT; ++i) {
|
||||
USER_LOG_DEBUG("position solution property: %d.", positionInfo[i].positionSolutionProperty);
|
||||
USER_LOG_DEBUG("pitchAttitudeAngle: %d\trollAttitudeAngle: %d\tyawAttitudeAngle: %d",
|
||||
USER_LOG_INFO("position solution property: %d.", positionInfo[i].positionSolutionProperty);
|
||||
USER_LOG_INFO("pitchAttitudeAngle: %d\trollAttitudeAngle: %d\tyawAttitudeAngle: %d",
|
||||
positionInfo[i].uavAttitude.pitch, positionInfo[i].uavAttitude.roll,
|
||||
positionInfo[i].uavAttitude.yaw);
|
||||
USER_LOG_DEBUG("northPositionOffset: %d\tearthPositionOffset: %d\tdownPositionOffset: %d",
|
||||
USER_LOG_INFO("northPositionOffset: %d\tearthPositionOffset: %d\tdownPositionOffset: %d",
|
||||
positionInfo[i].offsetBetweenMainAntennaAndTargetPoint.x,
|
||||
positionInfo[i].offsetBetweenMainAntennaAndTargetPoint.y,
|
||||
positionInfo[i].offsetBetweenMainAntennaAndTargetPoint.z);
|
||||
USER_LOG_DEBUG("longitude: %.8f\tlatitude: %.8f\theight: %.8f",
|
||||
USER_LOG_INFO("longitude: %.8f\tlatitude: %.8f\theight: %.8f",
|
||||
positionInfo[i].targetPointPosition.longitude,
|
||||
positionInfo[i].targetPointPosition.latitude,
|
||||
positionInfo[i].targetPointPosition.height);
|
||||
USER_LOG_DEBUG(
|
||||
USER_LOG_INFO(
|
||||
"longStandardDeviation: %.8f\tlatStandardDeviation: %.8f\thgtStandardDeviation: %.8f",
|
||||
positionInfo[i].targetPointPositionStandardDeviation.longitude,
|
||||
positionInfo[i].targetPointPositionStandardDeviation.latitude,
|
||||
|
||||
@ -89,7 +89,9 @@ T_DjiReturnCode DjiTest_PowerManagementStartService(void)
|
||||
|
||||
if (baseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V2 ||
|
||||
baseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_XPORT ||
|
||||
baseInfo.aircraftType == DJI_AIRCRAFT_TYPE_FC30) {
|
||||
baseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V3 ||
|
||||
baseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE ||
|
||||
baseInfo.aircraftType == DJI_AIRCRAFT_TYPE_FC30) {
|
||||
// apply high power
|
||||
if (s_applyHighPowerHandler.pinInit == NULL) {
|
||||
USER_LOG_ERROR("apply high power pin init interface is NULL error");
|
||||
@ -113,15 +115,31 @@ T_DjiReturnCode DjiTest_PowerManagementStartService(void)
|
||||
return returnCode;
|
||||
}
|
||||
|
||||
if (baseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_SKYPORT_V3 ||
|
||||
baseInfo.djiAdapterType == DJI_SDK_ADAPTER_TYPE_EPORT_V2_RIBBON_CABLE) {
|
||||
E_DjiHighPowerVoltage voltage = E_DJI_HIGH_POWER_VOLTAGE_17V;
|
||||
|
||||
USER_LOG_INFO("Start to apply high power.");
|
||||
USER_LOG_INFO("Start to apply high power.");
|
||||
|
||||
returnCode = DjiPowerManagement_ApplyHighPowerSync();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("apply high power error");
|
||||
return returnCode;
|
||||
returnCode = DjiPowerManagement_ApplyHighPowerSyncV2(voltage);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("apply high power error");
|
||||
return returnCode;
|
||||
}
|
||||
USER_LOG_INFO("Success to apply high power %s.",
|
||||
voltage == E_DJI_HIGH_POWER_VOLTAGE_13V6 ? "13V6" :
|
||||
voltage == E_DJI_HIGH_POWER_VOLTAGE_17V ? "17V" :
|
||||
voltage == E_DJI_HIGH_POWER_VOLTAGE_24V ? "24V" : "???");
|
||||
} else {
|
||||
USER_LOG_INFO("Start to apply high power.");
|
||||
|
||||
returnCode = DjiPowerManagement_ApplyHighPowerSync();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("apply high power error");
|
||||
return returnCode;
|
||||
}
|
||||
USER_LOG_INFO("Success to apply high power.");
|
||||
}
|
||||
USER_LOG_INFO("Success to apply high power.");
|
||||
}
|
||||
|
||||
// register power off notification callback function
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user