更新到psdk 3.13.0,适配M400

This commit is contained in:
tangchao0503
2025-09-10 16:03:18 +08:00
517 changed files with 197499 additions and 7197653 deletions

View File

@ -45,7 +45,6 @@ static const char *s_cameraManagerSampleSelectList[] = {
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_TAP_ZOOM_POINT] = "Set camera tap zoom point |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_ZOOM_PARAM] = "Set camera zoom param |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_SINGLE_PHOTO] = "Shoot single photo |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_AEB_PHOTO] = "Shoot aeb photo |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_BURST_PHOTO] = "Shoot busrt photo |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_INTERVAL_PHOTO] = "Shoot interval photo |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_RECORD_VIDEO] = "Record video |",
@ -54,6 +53,23 @@ static const char *s_cameraManagerSampleSelectList[] = {
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_THERMOMETRY] = "Thermometry test |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_GET_LIDAR_RANGING_INFO] = "Get lidar ranging info |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_IR_CAMERA_ZOOM_PARAM] = "Set ir camera zoom param |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_NIGHT_SCENE_MODE] = "Set night scene mode |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAPTURE_RECORDING_STREAMS] = "Set capture or recording streams storage type |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOW_STORAGE_INFO] = "Show storage info |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_FORMAT_SD_CARD] = "Format SD card |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_LINK_ZOOM] = "Set synchronized split screen zoom |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_USER_CUSTOM_DIR_FILE_NAME] = "Set custom directory or file name of media file |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_RESET_CAMERA_SETTINGS] = "Reset camera settings |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_AE_LOCK_MODE] = "Set AE lock mode |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_FOCUS_RING_VALUE] = "Set focus ring value |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_CONNECT_STATUS_TEST] = "Camera connect status test |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_GET_PHOTO_VIDEO_PARAM] = "Set camera photo and video storage param |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_METERING_MODE] = "Set camera metering mode |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_METERING_POINT] = "Set and get camera metering point |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_FFC_MODE_AND_TRRIGER] = "Set FFC mode and trriger a FFC |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_GAIN_MODE] = "Set infrared camera gain mode |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_GET_CAMERA_STATUS] = "Get camera status, capturing & recording status etc |",
[E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SUBSCRIBE_POINT_CLOUD] = "Subscribe point cloud |",
};
/* Private types -------------------------------------------------------------*/
@ -93,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 |"
<<
@ -118,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 {

View File

@ -0,0 +1,68 @@
{
"rc_lost_action": {
"desc_cn": "失控行为",
"desc_en": "rc lost action",
"desc_range": "go_home/hover/landing",
"value": "go_home"
},
"go_home_altitude": {
"desc_cn": "返航高度",
"desc_en": "go home altitude",
"desc_range": "0 - 1500",
"value": 60
},
"flying_speed": {
"desc_cn": "飞行速度",
"desc_en": "flying speed",
"desc_range": "0 - 10",
"value": 5.0
},
"home_point_latitude": {
"desc_cn": "home点纬度",
"desc_en": "home point latitude",
"desc_range": "-90 - 90",
"value": 22.5425
},
"home_point_longitude": {
"desc_cn": "home点经度",
"desc_en": "home point longitude",
"desc_range": "-180 - 180",
"value": 113.9575
},
"rtk_enable": {
"desc_cn": "RTK开关",
"desc_en": "RTK Enable",
"desc_range": "true/false",
"value": "false"
},
"HorizontalVisualObstacleAvoidanceEnable": {
"desc_cn": "水平视觉避障开关",
"desc_en": "Horizontal Visual Avoidance",
"desc_range": "true/false",
"value": "false"
},
"HorizontalRadarObstacleAvoidanceEnable": {
"desc_cn": "水平TOF避障开关",
"desc_en": "Horizontal TOF Avoidance",
"desc_range": "true/false",
"value": "false"
},
"UpwardsVisualObstacleAvoidanceEnable": {
"desc_cn": "上视觉避障开关",
"desc_en": "Upwards Visual Avoidance",
"desc_range": "true/false",
"value": "false"
},
"UpwardsRadarObstacleAvoidanceEnable": {
"desc_cn": "上TOF开关",
"desc_en": "Upwards TOF Avoidance",
"desc_range": "true/false",
"value": "false"
},
"DownwardsVisualObstacleAvoidanceEnable": {
"desc_cn": "下视觉避障开关",
"desc_en": "Downwards Visual Avoidance",
"desc_range": "true/false",
"value": "false"
}
}

View File

@ -0,0 +1,48 @@
/**
********************************************************************
* @file test_flight_controller_command_flying.h
* @brief This is the header file for "test_flight_controller_command_flying.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 DJIs 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_FLIGHT_CONTROLLER_COMMAND_FLYING_H
#define TEST_FLIGHT_CONTROLLER_COMMAND_FLYING_H
/* Includes ------------------------------------------------------------------*/
#ifdef __cplusplus
extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
void DjiUser_RunFlightControllerCommandFlyingSample(void);
#ifdef __cplusplus
}
#endif
#endif // TEST_FLIGHT_CONTROLLER_COMMAND_FLYING_H
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/

View File

@ -0,0 +1,127 @@
/**
********************************************************************
* @file test_flight_controller_entry.cpp
* @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 DJIs 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 <flight_control/test_flight_control.h>
#include "test_flight_controller_entry.h"
#include "dji_logger.h"
#include "test_flight_controller_command_flying.h"
#include <waypoint_v2/test_waypoint_v2.h>
#include <waypoint_v3/test_waypoint_v3.h>
#include <interest_point/test_interest_point.h>
/* Private constants ---------------------------------------------------------*/
/* Private types -------------------------------------------------------------*/
/* Private values -------------------------------------------------------------*/
/* Private functions declaration ---------------------------------------------*/
/* Exported functions definition ---------------------------------------------*/
void DjiUser_RunFlightControllerSample(void)
{
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
char inputSelectSample;
start:
osalHandler->TaskSleepMs(100);
std::cout
<< "\n"
<< "| Available commands: |\n"
<< "| [0] Flight controller sample - control flying with keyboard |\n"
<< "| [1] Flight controller sample - take off landing |\n"
<< "| [2] Flight controller sample - take off position ctrl landing |\n"
<< "| [3] Flight controller sample - take off go home force landing |\n"
<< "| [4] Flight controller sample - take off velocity ctrl landing |\n"
<< "| [5] Flight controller sample - arrest flying |\n"
<< "| [6] Flight controller sample - set get parameters |\n"
<< "| [7] Waypoint 2.0 sample - run airline mission by settings (only support on M300 RTK) |\n"
<< "| [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, support on M4/M4T/M4D/M4TD |\n"
<< "| [d] Select FTS pwm trigger position, support on M400 |\n"
<< std::endl;
std::cin >> inputSelectSample;
switch (inputSelectSample) {
case '0':
DjiUser_RunFlightControllerCommandFlyingSample();
goto start;
case '1':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_LANDING);
goto start;
case '2':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_POSITION_CTRL_LANDING);
goto start;
case '3':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_GO_HOME_FORCE_LANDING);
goto start;
case '4':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_VELOCITY_CTRL_LANDING);
goto start;
case '5':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_ARREST_FLYING);
goto start;
case '6':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SET_GET_PARAM);
goto start;
case '7':
DjiTest_WaypointV2RunSample();
break;
case '8':
DjiTest_WaypointV3RunSample();
break;
case '9':
DjiTest_InterestPointRunSample();
break;
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(DJI_MOUNT_POSITION_EXTENSION_PORT, "DJI_MOUNT_POSITION_EXTENSION_PORT");
// or DJI_MOUNT_POSITION_EXTENSION_LITE_PORT
DjiTest_FlightControlFtsPwmTriggerSample(DJI_MOUNT_POSITION_EXTENSION_LITE_PORT, "DJI_MOUNT_POSITION_EXTENSION_LITE_PORT");
break;
case 'd': // for m400
DjiTest_FlightControlFtsPwmTriggerSample(DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO4, "DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO4");
break;
case 'q':
break;
default:
USER_LOG_ERROR("Input command is invalid");
goto start;
}
}
/* Private functions definition-----------------------------------------------*/
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/

View File

@ -0,0 +1,49 @@
/**
********************************************************************
* @file test_flight_controller_entry.h
* @brief This is the header file for "test_flight_controller_entry.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 DJIs 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_FLIGHT_CONTROLLER_ENTRY_H
#define TEST_FLIGHT_CONTROLLER_ENTRY_H
/* Includes ------------------------------------------------------------------*/
#include <gimbal_manager/test_gimbal_manager.h>
#ifdef __cplusplus
extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
void DjiUser_RunFlightControllerSample(void);
#ifdef __cplusplus
}
#endif
#endif // TEST_FLIGHT_CONTROLLER_ENTRY_H
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/

View File

@ -29,7 +29,12 @@
#include "test_gimbal_entry.hpp"
#include "dji_logger.h"
#include "utils/util_misc.h"
#include "dji_gimbal.h"
#include "dji_gimbal_manager.h"
#include <iostream>
#include "dji_aircraft_info.h"
#include "dji_fc_subscription.h"
#include <math.h>
/* Private constants ---------------------------------------------------------*/
@ -37,6 +42,11 @@
typedef enum {
E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_ROTATE_GIMBAL_ON_FREE_MODE,
E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_ROTATE_GIMBAL_ON_YAW_FOLLOW_MODE,
E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_SET_PITCH_RANGE_EXTENSION_MODE,
E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_SET_CONTROLLER_MAX_SPEED_PERCENTAGE,
E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_SET_CONTROLLER_SMOOTH_FACTOR,
E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_RESET_GIMBAL_SETTINGS,
E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_ROTATE_GIMBAL_BY_KEYBOARD,
E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_QUIT,
} E_DjiTestGimbalManagerSampleSelect;
@ -46,6 +56,16 @@ static const char *s_gimbalManagerSampleList[] = {
"| [0] Gimbal manager sample - Rotate gimbal on free mode |",
[E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_ROTATE_GIMBAL_ON_YAW_FOLLOW_MODE] =
"| [1] Gimbal manager sample - Rotate gimbal on yaw follow mode |",
[E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_SET_PITCH_RANGE_EXTENSION_MODE] =
"| [2] Gimbal manager sample - Set pitch range extension mode |",
[E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_SET_CONTROLLER_MAX_SPEED_PERCENTAGE] =
"| [3] Gimbal manager sample - Set controller max speed percentage |",
[E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_SET_CONTROLLER_SMOOTH_FACTOR] =
"| [4] Gimbal manager sample - Set controller smooth factor |",
[E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_RESET_GIMBAL_SETTINGS] =
"| [5] Gimbal manager sample - Reset gimbal settings |",
[E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_ROTATE_GIMBAL_BY_KEYBOARD] =
"| [6] Gimbal manager sample - Rotate gimbal by keyboard input and read back value |",
[E_DJI_TEST_GIMBAL_MANAGER_SAMPLE_SELECT_QUIT] =
"| [q] Gimbal manager sample - Quit |",
};
@ -60,6 +80,7 @@ void DjiUser_RunGimbalManagerSample(void)
char inputTestCase;
char mountPosition;
E_DjiMountPosition gimbalMountPosition;
T_DjiReturnCode returnCode;
start:
osalHandler->TaskSleepMs(100);
@ -68,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
@ -89,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;
}
@ -110,6 +123,312 @@ start:
case '1':
DjiTest_GimbalManagerRunSample(gimbalMountPosition, DJI_GIMBAL_MODE_YAW_FOLLOW);
goto start;
case '2': {
int32_t enableFlag;
osalHandler->TaskSleepMs(10);
printf("Input enable flag: ");
scanf("%d", &enableFlag);
returnCode = DjiGimbalManager_Init();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Init gimbal manager error, return code 0x%08X", returnCode);
return;
}
returnCode = DjiGimbalManager_SetPitchRangeExtensionEnabled(gimbalMountPosition, (bool)enableFlag);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Failed!");
}
USER_LOG_INFO("Set gimbal's pitch range extension mode as %d successfully!", enableFlag);
goto start;
break;
}
case '3': {
int32_t percentage;
osalHandler->TaskSleepMs(10);
printf("Input max speed percentage of yaw axis: ");
scanf("%d", &percentage);
returnCode = DjiGimbalManager_Init();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Init gimbal manager error, return code 0x%08X", returnCode);
return;
}
returnCode = DjiGimbalManager_SetControllerMaxSpeedPercentage(gimbalMountPosition, DJI_GIMBAL_AXIS_YAW, (uint8_t)percentage);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Failed!");
}
USER_LOG_INFO("Set yaw axis's max speed percentage to %d successfully!", percentage);
osalHandler->TaskSleepMs(10);
printf("Input max speed percentage of pitch axis: ");
scanf("%d", &percentage);
returnCode = DjiGimbalManager_SetControllerMaxSpeedPercentage(gimbalMountPosition, DJI_GIMBAL_AXIS_PITCH, (uint8_t)percentage);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Failed!");
}
USER_LOG_INFO("Set pitch axis's max speed percentage to %d successfully!", percentage);
goto start;
break;
}
case '4': {
int32_t factor;
osalHandler->TaskSleepMs(10);
printf("Input yaw axis's smooth factor: ");
scanf("%d", &factor);
returnCode = DjiGimbalManager_Init();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Init gimbal manager error, return code 0x%08X", returnCode);
return;
}
returnCode = DjiGimbalManager_SetControllerSmoothFactor(gimbalMountPosition, DJI_GIMBAL_AXIS_YAW, (uint8_t)factor);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Failed!");
}
USER_LOG_INFO("Set yaw axis smooth factor to %d successfully!", factor);
osalHandler->TaskSleepMs(10);
printf("Input pitch axis's smooth factor: ");
scanf("%d", &factor);
returnCode = DjiGimbalManager_SetControllerSmoothFactor(gimbalMountPosition, DJI_GIMBAL_AXIS_PITCH, (uint8_t)factor);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Failed!");
}
USER_LOG_INFO("Set pitch axis smooth factor to %d successfully!", factor);
goto start;
break;
}
case '5': {
returnCode = DjiGimbalManager_Init();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Init gimbal manager error, return code 0x%08X", returnCode);
return;
}
returnCode = DjiGimbalManager_RestoreFactorySettings(gimbalMountPosition);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Failed!");
}
USER_LOG_INFO("Reset gimbal factory settings successfully!");
goto start;
break;
}
case '6': {
uint32_t gimbalMode;
uint32_t rotateMode;
dji_f32_t pitch, roll, yaw;
T_DjiGimbalManagerRotation rotation;
T_DjiAircraftInfoBaseInfo baseInfo;
E_DjiAircraftSeries aircraftSeries;
E_DjiFcSubscriptionTopic topicOfPayloadGimablAngle;
returnCode = DjiGimbalManager_Init();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Init gimbal manager error, return code 0x%08X", returnCode);
return;
}
returnCode = DjiAircraftInfo_GetBaseInfo(&baseInfo);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Failed to get aircraft base info, return code 0x%08X", returnCode);
goto end;
}
aircraftSeries = baseInfo.aircraftSeries;
if (aircraftSeries == DJI_AIRCRAFT_SERIES_M300 || aircraftSeries == DJI_AIRCRAFT_SERIES_M350) {
returnCode = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_IMU_ATTI_NAVI_DATA_WITH_TIMESTAMP, 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_IMU_ATTI_NAVI_DATA_WITH_TIMESTAMP, returnCode);
goto end;
}
returnCode = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_QUATERNION, 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_QUATERNION, returnCode);
goto end;
}
}
if (aircraftSeries == DJI_AIRCRAFT_SERIES_M300 || aircraftSeries == DJI_AIRCRAFT_SERIES_M350) {
returnCode = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_THREE_GIMBAL_DATA, 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_THREE_GIMBAL_DATA, returnCode);
goto end;
}
USER_LOG_INFO("Subscribe topic DJI_FC_SUBSCRIPTION_TOPIC_THREE_GIMBAL_DATA succefully.");
}
else if (aircraftSeries == DJI_AIRCRAFT_SERIES_M30 || aircraftSeries == DJI_AIRCRAFT_SERIES_M3 ||
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);
}
while (1) {
T_DjiFcSubscriptionQuaternion quat;
T_DjiFcSubscriptionThreeGimbalData threeGimbalData = {0};
T_DjiFcSubscriptionGimbalAngles gimbalAngles = {0};
T_DjiDataTimestamp timestamp = {0};
dji_f32_t nPitch, nRoll, nYaw;
dji_f32_t qPitch, qRoll, qYaw;
dji_f32_t yawOffset = 0;
T_DjiFcSubscriptionImuAttiNaviDataWithTimestamp naviData = {0};
osalHandler->TaskSleepMs(5);
printf("gimbal mode: 0: free, 1: fpv, 2: yaw-follow, 3: exit sample\n");
printf("rotate mode: 0: rel, 1: abs\n");
printf("Input gimbal mode, rotate mode, p, r, y(range in 0 ~ 360 deg if in abs mode): ");
scanf("%d", &gimbalMode);
if (gimbalMode == 3) {
break;
}
scanf("%d %f %f %f", &rotateMode, &pitch, &roll, &yaw);
printf("gimbale mode %d, rotate mode %d, p %f, r %f, y %f\n",
gimbalMode, rotateMode, pitch, roll, yaw);
returnCode = DjiGimbalManager_SetMode(gimbalMountPosition, (E_DjiGimbalMode)gimbalMode);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("DjiGimbalManager_SetMode return 0x%08X", returnCode);
goto end;
}
rotation.rotationMode = (E_DjiGimbalRotationMode)rotateMode;
rotation.pitch = pitch;
rotation.roll = roll;
rotation.yaw = yaw;
rotation.time = 0.5;
if (aircraftSeries == DJI_AIRCRAFT_SERIES_M300 || aircraftSeries == DJI_AIRCRAFT_SERIES_M350) {
osalHandler->TaskSleepMs(20);
returnCode = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_IMU_ATTI_NAVI_DATA_WITH_TIMESTAMP,
(uint8_t *) &naviData,
sizeof(T_DjiFcSubscriptionImuAttiNaviDataWithTimestamp),
&timestamp);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("returnCode = 0x%08X", returnCode);
}
nYaw = (dji_f64_t) atan2f(2 * naviData.q[1] * naviData.q[2] + 2 * naviData.q[0] * naviData.q[3],
-2 * naviData.q[2] * naviData.q[2] - 2 * naviData.q[3] * naviData.q[3] + 1) * 57.3;
returnCode = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_QUATERNION,
(uint8_t *) &quat,
sizeof(T_DjiFcSubscriptionQuaternion),
&timestamp);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("DjiFcSubscription_GetLatestValueOfTopic return %x%08X", returnCode);
goto end;
}
qYaw = (dji_f64_t) atan2f(2 * quat.q1 * quat.q2 + 2 * quat.q0 * quat.q3,
-2 * quat.q2 * quat.q2 - 2 * quat.q3 * quat.q3 + 1) * 57.3;
yawOffset = nYaw - qYaw;
if (rotation.rotationMode == DJI_GIMBAL_ROTATION_MODE_ABSOLUTE_ANGLE) {
rotation.yaw += yawOffset;
}
}
returnCode = DjiGimbalManager_Rotate(gimbalMountPosition, rotation);
if (returnCode == DJI_ERROR_GIMBAL_MODULE_CODE_PITCH_REACH_POSITIVE_LIMIT ||
returnCode == DJI_ERROR_GIMBAL_MODULE_CODE_PITCH_REACH_NEGATIVE_LIMIT ||
returnCode == DJI_ERROR_GIMBAL_MODULE_CODE_ROLL_REACH_POSITIVE_LIMIT ||
returnCode == DJI_ERROR_GIMBAL_MODULE_CODE_ROLL_REACH_NEGATIVE_LIMIT ||
returnCode == DJI_ERROR_GIMBAL_MODULE_CODE_YAW_REACH_POSITIVE_LIMIT ||
returnCode == DJI_ERROR_GIMBAL_MODULE_CODE_YAW_REACH_NEGATIVE_LIMIT) {
USER_LOG_WARN("Reach limitation!");
}
else if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("DjiGimbalManager_Rotate return %x%08X", returnCode);
goto end;
}
osalHandler->TaskSleepMs(2000);
if (aircraftSeries == DJI_AIRCRAFT_SERIES_M300 || aircraftSeries == DJI_AIRCRAFT_SERIES_M350) {
returnCode = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_THREE_GIMBAL_DATA,
(uint8_t *) &threeGimbalData,
sizeof(T_DjiFcSubscriptionThreeGimbalData),
&timestamp);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("DjiFcSubscription_GetLatestValueOfTopic return %x%08X", returnCode);
goto end;
}
if (threeGimbalData.anglesData[0].yaw < 0) {
threeGimbalData.anglesData[0].yaw = 360 + threeGimbalData.anglesData[0].yaw;
}
USER_LOG_INFO("reab back gimbal's (p, r, y): p=%.4f r=%.4f y=%.4f",
threeGimbalData.anglesData[gimbalMountPosition - 1].pitch,
threeGimbalData.anglesData[gimbalMountPosition - 1].roll,
threeGimbalData.anglesData[gimbalMountPosition - 1].yaw);
}
else if (aircraftSeries == DJI_AIRCRAFT_SERIES_M30 || aircraftSeries == DJI_AIRCRAFT_SERIES_M3 ||
aircraftSeries == DJI_AIRCRAFT_SERIES_M3D || aircraftSeries == DJI_AIRCRAFT_SERIES_M400) {
returnCode = DjiFcSubscription_GetLatestValueOfTopic(topicOfPayloadGimablAngle,
(uint8_t *) &gimbalAngles,
sizeof(T_DjiFcSubscriptionGimbalAngles),
&timestamp);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("DjiFcSubscription_GetLatestValueOfTopic return %x%08X", returnCode);
goto end;
}
if (gimbalAngles.z < 0) {
gimbalAngles.z = 360 + gimbalAngles.z;
}
USER_LOG_INFO("read back gimbal's (p, r, y): p=%.4f r=%.4f y=%.4f",
gimbalAngles.x, gimbalAngles.y, gimbalAngles.z);
}
}
break;
}
case 'q':
break;
default:
@ -117,6 +436,15 @@ start:
goto start;
}
end:
returnCode = DjiGimbalManager_Deinit();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Deinit gimbal manager error, return code 0x%08X", returnCode);
return;
}
USER_LOG_INFO("Gimbal sample end");
return;
}
/* Private functions definition-----------------------------------------------*/

View File

@ -0,0 +1,115 @@
/**
********************************************************************
* @file hms_manager_entry.cpp
* @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 DJIs 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 "hms_manager_entry.h"
#include "dji_platform.h"
#include <iostream>
#include "dji_logger.h"
#include "hms/test_hms.h"
#include "dji_hms_customization.h"
/* Private constants ---------------------------------------------------------*/
/* Private types -------------------------------------------------------------*/
/* Private values -------------------------------------------------------------*/
/* Private functions declaration ---------------------------------------------*/
/* Exported functions definition ---------------------------------------------*/
void DjiUser_RunHmsManagerSample(void)
{
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
char inputSelectSample;
start:
osalHandler->TaskSleepMs(100);
std::cout
<< "\n"
<< "| Available commands: |\n"
<< "| [0] Hms manager sample - Chinese language |\n"
<< "| [1] Hms manager sample - English language |\n"
<< "| [2] Hms manager sample - Japanese language |\n"
<< "| [3] Hms manager sample - French language |\n"
<< std::endl;
std::cin >> inputSelectSample;
switch (inputSelectSample) {
case '0':
DjiTest_HmsManagerRunSample(DJI_MOBILE_APP_LANGUAGE_CHINESE);
goto start;
case '1':
DjiTest_HmsManagerRunSample(DJI_MOBILE_APP_LANGUAGE_ENGLISH);
goto start;
case '2':
DjiTest_HmsManagerRunSample(DJI_MOBILE_APP_LANGUAGE_JAPANESE);
goto start;
case '3':
DjiTest_HmsManagerRunSample(DJI_MOBILE_APP_LANGUAGE_FRENCH);
goto start;
case 'q':
break;
default:
USER_LOG_ERROR("Input command is invalid");
goto 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****/

View File

@ -0,0 +1,50 @@
/**
********************************************************************
* @file hms_manager_entry.h
* @brief This is the header file for "hms_manager_entry.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 DJIs 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 HMS_MANAGER_ENTRY_H
#define HMS_MANAGER_ENTRY_H
/* Includes ------------------------------------------------------------------*/
#ifdef __cplusplus
extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
void DjiUser_RunHmsManagerSample(void);
void DjiUser_RunHmsEnhanceSample(void);
#ifdef __cplusplus
}
#endif
#endif // HMS_MANAGER_ENTRY_H
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/

View File

@ -0,0 +1,6 @@
classes= 80
train = ~/COCO/train2017.txt
valid = ~/COCO/val2017.txt
names = coco.names
backup = model

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -0,0 +1,665 @@
/**
********************************************************************
*
* @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 DJIs 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 <sys/stat.h>
#include <sys/types.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 "dji_aircraft_info.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 T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo;
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();
USER_LOG_INFO("Input cammera sourece(1:1080p, 3:M4 serials 4K, 7:H30 serials 4K): ");
std::cin >> mediaSource;
if (pos < 1 || pos > 3 || mediaSource > 7)
{
USER_LOG_ERROR("invalid param");
return;
}
std::string timestamp = getCurrentTimestamp();
// avoid miss dir error
mkdir ("data", 0755);
std::string h264FileName = "data/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;
}
returnCode = DjiAircraftInfo_GetBaseInfo(&aircraftInfoBaseInfo);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("get aircraft base info error");
return;
}
#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);
if (aircraftInfoBaseInfo.aircraftSeries != DJI_AIRCRAFT_SERIES_M4D)
{
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;
}

View File

@ -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 DJIs 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******/

View 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 DJIs 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

View File

@ -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 DJIs 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

View File

@ -42,7 +42,7 @@ LiveviewSample::LiveviewSample()
returnCode = DjiLiveview_Init();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
perror("Liveview init failed");
throw ("Liveview init failed");
}
streamDecoder = {

View File

@ -82,9 +82,15 @@ void DjiUser_RunCameraStreamViewSample()
char mainName[] = "MAIN_CAM";
char viceName[] = "VICE_CAM";
char topName[] = "TOP_CAM";
auto *liveviewSample = new LiveviewSample();
T_DjiReturnCode returnCode;
LiveviewSample *liveviewSample;
try {
liveviewSample = new LiveviewSample();
} catch (...) {
return;
}
returnCode = DjiUser_GetCurrentFileDirPath(__FILE__, DJI_FILE_PATH_SIZE_MAX, curFileDirPath);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Get file current path error, stat = 0x%08llX", returnCode);
@ -204,17 +210,9 @@ static void DjiUser_ShowRgbImageCallback(CameraRGBImage img, void *userData)
cout << " x: " << faces[i].x;
cout << " y: " << faces[i].y << endl;
#ifdef OPEN_CV_VERSION_3
cv::rectangle(mat, cvPoint(faces[i].x, faces[i].y),
cvPoint(faces[i].x + faces[i].width, faces[i].y + faces[i].height),
Scalar(0, 0, 255), 2, 1, 0);
#endif
#ifdef OPEN_CV_VERSION_4
cv::rectangle(mat, cv::Point(faces[i].x, faces[i].y),
cv::Point(faces[i].x + faces[i].width, faces[i].y + faces[i].height),
Scalar(0, 0, 255), 2, 1, 0);
#endif
}
imshow(name, mat);
} else if (s_demoIndex == 3) {
@ -273,15 +271,8 @@ static void DjiUser_ShowRgbImageCallback(CameraRGBImage img, void *userData)
int baseLine = 0;
Size labelSize = getTextSize(label, FONT_HERSHEY_SIMPLEX, 0.5, 1, &baseLine);
#ifdef OPEN_CV_VERSION_3
rectangle(mat, Rect(Point(xLeftBottom, yLeftBottom - labelSize.height),
Size(labelSize.width, labelSize.height + baseLine)), Scalar(0, 255, 0), CV_FILLED);
#endif
#ifdef OPEN_CV_VERSION_4
rectangle(mat, Rect(Point(xLeftBottom, yLeftBottom - labelSize.height),
Size(labelSize.width, labelSize.height + baseLine)), Scalar(0, 255, 0), cv::FILLED);
#endif
putText(mat, label, Point(xLeftBottom, yLeftBottom), FONT_HERSHEY_SIMPLEX, 0.5, Scalar(0, 0, 0));
}
}

View 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 DJIs 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****/

View 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 DJIs 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******/

View File

@ -46,7 +46,7 @@ PerceptionSample::PerceptionSample()
USER_LOG_ERROR("Perception feature will support on later version.");
}
perror("Perception init failed");
throw ("Perception init failed");
}
}

View File

@ -103,10 +103,16 @@ void DjiUser_RunStereoVisionViewSample(void)
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
char inputChar;
char isQuit;
auto *perceptionSample = new PerceptionSample;
T_DjiReturnCode returnCode;
T_DjiPerceptionCameraParametersPacket cameraParametersPacket = {0};
PerceptionSample *perceptionSample;
try {
perceptionSample = new PerceptionSample;
} catch (...) {
return;
}
returnCode = osalHandler->MutexCreate(&s_stereoImagePacket.mutex);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Crete mutex failed, return code:0x%08X", returnCode);
@ -206,27 +212,27 @@ void DjiUser_RunStereoVisionViewSample(void)
switch (inputChar) {
case 'd':
USER_LOG_INFO("Subscribe down stereo camera pair images.");
perceptionSample->SubscribeDownImage(DjiTest_PerceptionImageCallback);
returnCode = perceptionSample->SubscribeDownImage(DjiTest_PerceptionImageCallback);
break;
case 'f':
USER_LOG_INFO("Subscribe front stereo camera pair images.");
perceptionSample->SubscribeFrontImage(DjiTest_PerceptionImageCallback);
returnCode = perceptionSample->SubscribeFrontImage(DjiTest_PerceptionImageCallback);
break;
case 'r':
USER_LOG_INFO("Subscribe rear stereo camera pair images.");
perceptionSample->SubscribeRearImage(DjiTest_PerceptionImageCallback);
returnCode = perceptionSample->SubscribeRearImage(DjiTest_PerceptionImageCallback);
break;
case 'u':
USER_LOG_INFO("Subscribe up stereo camera pair images.");
perceptionSample->SubscribeUpImage(DjiTest_PerceptionImageCallback);
returnCode = perceptionSample->SubscribeUpImage(DjiTest_PerceptionImageCallback);
break;
case 'l':
USER_LOG_INFO("Subscribe left stereo camera pair images.");
perceptionSample->SubscribeLeftImage(DjiTest_PerceptionImageCallback);
returnCode = perceptionSample->SubscribeLeftImage(DjiTest_PerceptionImageCallback);
break;
case 't':
USER_LOG_INFO("Subscribe right stereo camera pair images.");
perceptionSample->SubscribeRightImage(DjiTest_PerceptionImageCallback);
returnCode = perceptionSample->SubscribeRightImage(DjiTest_PerceptionImageCallback);
break;
case 'g':
USER_LOG_INFO("Do stereo camera parameters subscription");
@ -237,6 +243,11 @@ void DjiUser_RunStereoVisionViewSample(void)
break;
}
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_INFO("Failed to subscribe perception image.");
goto DestroyTask;
}
while (true) {
cin >> isQuit;
if (isQuit == 'q' || isQuit == 'Q') {
@ -373,15 +384,8 @@ static void *DjiTest_StereoImagesDisplayTask(void *arg)
sprintf(&showFpsString[i][0], "%s%d", fpsStr, fps);
}
timePrev[i] = timeNow[i];
#ifdef OPEN_CV_VERSION_3
cv::putText(cv_img_stereo, &showFpsString[i][0], cv::Point(5, 20),
CV_FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(0, 0, 0));
#endif
#ifdef OPEN_CV_VERSION_4
cv::putText(cv_img_stereo, &showFpsString[i][0], cv::Point(5, 20),
cv::FONT_HERSHEY_SIMPLEX, 0.5, cv::Scalar(0, 0, 0));
#endif
}
cv::imshow(nameStr, cv_img_stereo);
cv::waitKey(1);

View 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 DJIs 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****/

View 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 DJIs 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******/

View File

@ -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 DJIs 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, &param);
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, &param);
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, &param);
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, &param);
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****/

View 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 DJIs 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******/

View File

@ -320,7 +320,7 @@ T_DjiReturnCode Osal_GetTimeUs(uint64_t *us)
if (s_localTimeUsOffset == 0) {
s_localTimeUsOffset = *us;
} else {
*us = *us - s_localTimeMsOffset;
*us = *us - s_localTimeUsOffset;
}
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;

View 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)

View File

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

View File

@ -31,6 +31,8 @@ file(GLOB_RECURSE MODULE_SAMPLE_SRC
../../../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
)
file(GLOB_RECURSE MODULE_COMMON_SRC ../common/*.c*)
@ -44,7 +46,7 @@ if (DEVICE_SYSTEM_ID MATCHES x86_64)
add_definitions(-DPLATFORM_ARCH_x86_64=1)
elseif (DEVICE_SYSTEM_ID MATCHES aarch64)
set(TOOLCHAIN_NAME aarch64-linux-gnu-gcc)
add_definitions(-DPLATFORM_ARCH_aarch64=1)
add_definitions(-DPLATFORM_ARCH_AARCH64=1)
else ()
message(FATAL_ERROR "FATAL: Please confirm your platform.")
endif ()
@ -69,12 +71,6 @@ if (OpenCV_FOUND)
message(STATUS " - Includes: ${OpenCV_INCLUDE_DIRS}")
message(STATUS " - Libraries: ${OpenCV_LIBRARIES}")
add_definitions(-DOPEN_CV_INSTALLED)
execute_process(COMMAND opencv_version OUTPUT_VARIABLE OPENCV_VERSION)
if (${OPENCV_VERSION} STRLESS "4.0.0")
add_definitions(-DOPEN_CV_VERSION_3)
else()
add_definitions(-DOPEN_CV_VERSION_4)
endif()
else ()
message(STATUS "Did not find OpenCV in the system, image data is inside RecvContainer as raw data")
endif ()
@ -86,10 +82,10 @@ if (FFMPEG_FOUND)
message(STATUS " - Libraries: ${FFMPEG_LIBRARIES}")
EXECUTE_PROCESS(COMMAND ffmpeg -version
OUTPUT_VARIABLE ffmpeg_version_psdk_libput
OUTPUT_VARIABLE ffmpeg_version_output
OUTPUT_STRIP_TRAILING_WHITESPACE
)
string(REGEX MATCH "version.*Copyright" ffmpeg_version_line ${ffmpeg_version_psdk_libput})
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})
@ -137,11 +133,10 @@ endif ()
target_link_libraries(${PROJECT_NAME} m)
add_custom_command(TARGET ${PROJECT_NAME}
PRE_LINK COMMAND cmake ..
WORKING_DIRECTORY ${CMAKE_BINARY_DIR})
target_include_directories(${PROJECT_NAME} PRIVATE ${OpenCV_INCLUDE_DIRS})
if (OpenCV_FOUND)
target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS})
endif ()
target_link_libraries(${PROJECT_NAME} dl)

View File

@ -39,9 +39,18 @@
#include "../manifold2/hal/hal_uart.h"
#include "../manifold2/hal/hal_network.h"
#include "utils/dji_config_manager.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/latest"
#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)
@ -52,6 +61,8 @@
#define USER_UTIL_MIN(a, b) (((a) < (b)) ? (a) : (b))
#define USER_UTIL_MAX(a, b) (((a) > (b)) ? (a) : (b))
#define DJI_USE_SDK_CONFIG_BY_JSON (0)
/* Private types -------------------------------------------------------------*/
/* Private values -------------------------------------------------------------*/
@ -60,11 +71,13 @@ 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_SetupEnvironment(argc, argv);
Application::DjiUser_ApplicationStart();
Osal_TaskSleepMs(3000);
@ -74,7 +87,7 @@ Application::~Application()
= default;
/* Private functions definition-----------------------------------------------*/
void Application::DjiUser_SetupEnvironment()
void Application::DjiUser_SetupEnvironment(int argc, char **argv)
{
T_DjiReturnCode returnCode;
T_DjiOsalHandler osalHandler = {0};
@ -83,8 +96,9 @@ void Application::DjiUser_SetupEnvironment()
T_DjiLoggerConsole printConsole;
T_DjiLoggerConsole localRecordConsole;
T_DjiFileSystemHandler fileSystemHandler = {0};
T_DjiSocketHandler socketHandler {0};
T_DjiSocketHandler socketHandler{0};
T_DjiHalNetworkHandler networkHandler = {0};
T_DjiUserLinkConfig linkConfig;
networkHandler.NetworkInit = HalNetWork_Init;
networkHandler.NetworkDeInit = HalNetWork_DeInit;
@ -163,6 +177,28 @@ void Application::DjiUser_SetupEnvironment()
throw std::runtime_error("Register hal uart handler error.");
}
#if DJI_USE_SDK_CONFIG_BY_JSON
if (argc > 1) {
DjiUserConfigManager_LoadConfiguration(argv[1]);
} else {
DjiUserConfigManager_LoadConfiguration(nullptr);
}
DjiUserConfigManager_GetLinkConfig(&linkConfig);
if (linkConfig.type == DJI_USER_LINK_CONFIG_USE_UART_AND_NETWORK_DEVICE) {
returnCode = DjiPlatform_RegHalNetworkHandler(&networkHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Register hal network handler error");
}
} else if (linkConfig.type == DJI_USER_LINK_CONFIG_USE_UART_AND_USB_BULK_DEVICE) {
returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Register hal usb bulk handler error.");
}
} else {
/*!< Attention: Only use uart hardware connection. */
}
#else
#if (CONFIG_HARDWARE_CONNECTION == DJI_USE_UART_AND_USB_BULK_DEVICE)
returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
@ -176,6 +212,7 @@ void Application::DjiUser_SetupEnvironment()
#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_UART)
/*!< Attention: Only use uart hardware connection.
*/
#endif
#endif
//Attention: if you want to use camera stream view function, please uncomment it.
@ -219,13 +256,18 @@ void Application::DjiUser_ApplicationStart()
// attention: when the program is hand up ctrl-c will generate the coredump file
signal(SIGTERM, DjiUser_NormalExitHandler);
#if DJI_USE_SDK_CONFIG_BY_JSON
DjiUserConfigManager_GetAppInfo(&userInfo);
#else
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.");
}
#endif
returnCode = DjiCore_Init(&userInfo);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
sleep(1);
throw std::runtime_error("Core init error.");
}
@ -234,7 +276,8 @@ void Application::DjiUser_ApplicationStart()
throw std::runtime_error("Get aircraft base info error.");
}
if (aircraftInfoBaseInfo.mountPosition != DJI_MOUNT_POSITION_EXTENSION_PORT) {
if (aircraftInfoBaseInfo.mountPosition != DJI_MOUNT_POSITION_EXTENSION_PORT
&& DJI_MOUNT_POSITION_EXTENSION_LITE_PORT != aircraftInfoBaseInfo.mountPosition) {
throw std::runtime_error("Please run this sample on extension port.");
}
@ -253,6 +296,65 @@ void Application::DjiUser_ApplicationStart()
throw std::runtime_error("Set serial number 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.");
@ -408,6 +510,8 @@ T_DjiReturnCode Application::DjiUser_LocalWriteFsInit(const char *path)
}
}
sprintf(systemCmd, "ln -sfrv %s " DJI_LOG_FOLDER_NAME "/latest.log", filePath);
system(systemCmd);
return djiReturnCode;
}
@ -417,4 +521,15 @@ static void DjiUser_NormalExitHandler(int 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****/

View File

@ -48,7 +48,7 @@ public:
~Application();
private:
static void DjiUser_SetupEnvironment();
static void DjiUser_SetupEnvironment(int argc, char **argv);
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);

View File

@ -40,7 +40,19 @@ extern "C" {
/*!< Attention: Select your hardware connection mode here.
* */
#define CONFIG_HARDWARE_CONNECTION DJI_USE_UART_AND_NETWORK_DEVICE
#define CONFIG_HARDWARE_CONNECTION DJI_USE_ONLY_UART
/*!< Attention: Select the sample you want to run here.
* */
#define CONFIG_MODULE_SAMPLE_GIMBAL_EMU_ON
#define CONFIG_MODULE_SAMPLE_WIDGET_ON
#define CONFIG_MODULE_SAMPLE_WIDGET_SPEAKER_ON
#define CONFIG_MODULE_SAMPLE_POWER_MANAGEMENT_ON
#define CONFIG_MODULE_SAMPLE_DATA_TRANSMISSION_ON
/* Exported types ------------------------------------------------------------*/

View File

@ -0,0 +1,36 @@
{
"dji_sdk_app_info": {
"user_app_name": "your_app_name",
"user_app_id": "your_app_id",
"user_app_key": "your_app_key",
"user_app_license": "your_app_license",
"user_develop_account": "your_developer_account",
"user_baud_rate": "460800"
},
"dji_sdk_link_config": {
"link_available": "use_only_uart/use_uart_and_usb_bulk_device/use_uart_and_network_device",
"link_select": "use_uart_and_network_device",
"uart_config": {
"uart1_device_name": "/dev/ttyUSB0",
"uart2_device_enable": "true",
"uart2_device_name": "/dev/ttyACM0"
},
"network_config": {
"network_device_name": "enxf8e43b7bbc2c",
"network_usb_adapter_vid": "0x0B95",
"network_usb_adapter_pid": "0x1790"
},
"usb_bulk_config": {
"usb_device_vid": "0x0B95",
"usb_device_pid": "0x1790",
"usb_bulk1_device_name": "/dev/usb-ffs/bulk1",
"usb_bulk1_interface_num": "2",
"usb_bulk1_endpoint_in": "0x83",
"usb_bulk1_endpoint_out": "0x02",
"usb_bulk2_device_name": "/dev/usb-ffs/bulk2",
"usb_bulk2_interface_num": "3",
"usb_bulk2_endpoint_in": "0x84",
"usb_bulk2_endpoint_out": "0x03"
}
}
}

View File

@ -25,11 +25,10 @@
/* 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 <hms/test_hms.h>
#include <waypoint_v2/test_waypoint_v2.h>
#include <waypoint_v3/test_waypoint_v3.h>
#include "application.hpp"
#include "fc_subscription/test_fc_subscription.h"
#include <gimbal_emu/test_payload_gimbal_emu.h>
@ -40,7 +39,9 @@
#include "widget/test_widget_speaker.h"
#include <power_management/test_power_management.h>
#include "data_transmission/test_data_transmission.h"
#include <camera_manager/test_camera_manager.h>
#include <flight_controller/test_flight_controller_entry.h>
#include <positioning/test_positioning.h>
#include <hms_manager/hms_manager_entry.h>
#include "camera_manager/test_camera_manager_entry.h"
/* Private constants ---------------------------------------------------------*/
@ -50,8 +51,6 @@
/* Private values -------------------------------------------------------------*/
/* Private functions declaration ---------------------------------------------*/
static T_DjiReturnCode DjiTest_HighPowerApplyPinInit();
static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState);
/* Exported functions definition ---------------------------------------------*/
int main(int argc, char **argv)
@ -67,25 +66,15 @@ start:
<< "\n"
<< "| Available commands: |\n"
<< "| [0] Fc subscribe sample - subscribe quaternion and gps data |\n"
<< "| [1] Flight controller sample - take off landing |\n"
<< "| [2] Flight controller sample - take off position ctrl landing |\n"
<< "| [3] Flight controller sample - take off go home force landing |\n"
<< "| [4] Flight controller sample - take off velocity ctrl landing |\n"
<< "| [5] Flight controller sample - arrest flying |\n"
<< "| [6] Flight controller sample - set get parameters |\n"
<< "| [7] Hms info sample - get health manger system info |\n"
<< "| [8] Waypoint 2.0 sample - run airline mission by settings (only support on M300 RTK) |\n"
<< "| [9] Waypoint 3.0 sample - run airline mission by kmz file (not support on M300 RTK) |\n"
<< "| [a] Gimbal manager sample |\n"
<< "| [1] Flight controller sample - you can control flying by PSDK |\n"
<< "| [2] Hms info manager sample - get health manger system info by language |\n"
<< "| [a] Gimbal manager sample - you can control gimbal by PSDK |\n"
<< "| [c] Camera stream view sample - display the camera video stream |\n"
<< "| [d] Stereo vision view sample - display the stereo image |\n"
<< "| [e] Start camera all features sample - you can operate the camera on DJI Pilot |\n"
<< "| [f] Start gimbal all features sample - you can operate the gimbal on DJI Pilot |\n"
<< "| [g] Start widget all features sample - you can operate the widget on DJI Pilot |\n"
<< "| [h] Start widget speaker sample - you can operate the speaker on DJI Pilot2 |\n"
<< "| [i] Start power management sample - you will see notification when aircraft power off |\n"
<< "| [j] Start data transmission sample - you can send or recv custom data on MSDK demo |\n"
<< "| [k] Run camera manager sample - you can test camera's functions interactively |\n"
<< "| [e] Run camera manager sample - you can test camera's functions interactively |\n"
<< "| [f] Start rtk positioning sample - you can receive rtk rtcm data when rtk signal is ok |\n"
<< "| [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;
@ -94,31 +83,10 @@ start:
DjiTest_FcSubscriptionRunSample();
break;
case '1':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_LANDING);
DjiUser_RunFlightControllerSample();
break;
case '2':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_POSITION_CTRL_LANDING);
break;
case '3':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_GO_HOME_FORCE_LANDING);
break;
case '4':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_VELOCITY_CTRL_LANDING);
break;
case '5':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_ARREST_FLYING);
break;
case '6':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SET_GET_PARAM);
break;
case '7':
DjiTest_HmsRunSample();
break;
case '8':
DjiTest_WaypointV2RunSample();
break;
case '9':
DjiTest_WaypointV3RunSample();
DjiUser_RunHmsManagerSample();
break;
case 'a':
DjiUser_RunGimbalManagerSample();
@ -130,77 +98,22 @@ start:
DjiUser_RunStereoVisionViewSample();
break;
case 'e':
returnCode = DjiTest_CameraEmuBaseStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("camera emu common init error");
break;
}
if (DjiPlatform_GetSocketHandler() != nullptr) {
returnCode = DjiTest_CameraEmuMediaStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("camera emu media init error");
break;
}
}
USER_LOG_INFO("Start camera all feautes sample successfully");
DjiUser_RunCameraManagerSample();
break;
case 'f':
if (DjiTest_GimbalStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("psdk gimbal init error");
returnCode = DjiTest_PositioningStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("rtk positioning sample init error");
break;
}
USER_LOG_INFO("Start gimbal all feautes sample successfully");
USER_LOG_INFO("Start rtk positioning sample successfully");
break;
case 'g':
returnCode = DjiTest_WidgetStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("widget sample init error");
break;
}
USER_LOG_INFO("Start widget all feautes sample successfully");
DjiUser_RunLidarDataSubscriptionSample();
break;
case 'h':
returnCode = DjiTest_WidgetSpeakerStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("widget speaker test init error");
break;
}
USER_LOG_INFO("Start widget speaker sample successfully");
break;
case 'i':
applyHighPowerHandler.pinInit = DjiTest_HighPowerApplyPinInit;
applyHighPowerHandler.pinWrite = DjiTest_WriteHighPowerApplyPin;
returnCode = DjiTest_RegApplyHighPowerHandler(&applyHighPowerHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("regsiter apply high power handler error");
break;
}
returnCode = DjiTest_PowerManagementStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("power management init error");
break;
}
USER_LOG_INFO("Start power management sample successfully");
break;
case 'j':
returnCode = DjiTest_DataTransmissionStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("data transmission sample init error");
break;
}
USER_LOG_INFO("Start data transmission sample successfully");
break;
case 'k':
DjiUser_RunCameraManagerSample();
DjiUser_RunRadarDataSubscriptionSample();
break;
default:
break;
@ -212,15 +125,5 @@ start:
}
/* Private functions definition-----------------------------------------------*/
static T_DjiReturnCode DjiTest_HighPowerApplyPinInit()
{
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState)
{
//attention: please pull up the HWPR pin state by hardware.
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/

View File

@ -30,6 +30,7 @@
#include "stdio.h"
#include "hal_network.h"
#include "dji_logger.h"
#include "utils/dji_config_manager.h"
/* Private constants ---------------------------------------------------------*/
@ -44,6 +45,8 @@ T_DjiReturnCode HalNetWork_Init(const char *ipAddr, const char *netMask, T_DjiNe
{
int32_t ret;
char cmdStr[LINUX_CMD_STR_MAX_SIZE];
char networkDeviceName[USER_DEVICE_NAME_STR_MAX_SIZE];
T_DjiUserLinkConfig linkConfig = {0};
if (ipAddr == NULL || netMask == NULL) {
USER_LOG_ERROR("hal network config param error");
@ -53,7 +56,14 @@ T_DjiReturnCode HalNetWork_Init(const char *ipAddr, const char *netMask, T_DjiNe
//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);
if (DjiUserConfigManager_IsEnable()) {
DjiUserConfigManager_GetLinkConfig(&linkConfig);
strcpy(networkDeviceName, linkConfig.networkConfig.networkDeviceName);
} else {
strcpy(networkDeviceName, LINUX_NETWORK_DEV);
}
snprintf(cmdStr, sizeof(cmdStr), "ifconfig %s up", networkDeviceName);
ret = system(cmdStr);
if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Can't open the network."
@ -62,7 +72,7 @@ T_DjiReturnCode HalNetWork_Init(const char *ipAddr, const char *netMask, T_DjiNe
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
snprintf(cmdStr, sizeof(cmdStr), "ifconfig %s %s netmask %s", LINUX_NETWORK_DEV, ipAddr, netMask);
snprintf(cmdStr, sizeof(cmdStr), "ifconfig %s %s netmask %s", networkDeviceName, ipAddr, netMask);
ret = system(cmdStr);
if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Can't config the ip address of network."
@ -81,8 +91,16 @@ T_DjiReturnCode HalNetWork_DeInit(T_DjiNetworkHandle halObj)
T_DjiReturnCode HalNetWork_GetDeviceInfo(T_DjiHalNetworkDeviceInfo *deviceInfo)
{
deviceInfo->usbNetAdapter.vid = USB_NET_ADAPTER_VID;
deviceInfo->usbNetAdapter.pid = USB_NET_ADAPTER_PID;
T_DjiUserLinkConfig linkConfig = {0};
if (DjiUserConfigManager_IsEnable()) {
DjiUserConfigManager_GetLinkConfig(&linkConfig);
deviceInfo->usbNetAdapter.vid = linkConfig.networkConfig.networkUsbAdapterVid;
deviceInfo->usbNetAdapter.pid = linkConfig.networkConfig.networkUsbAdapterPid;
} else {
deviceInfo->usbNetAdapter.vid = USB_NET_ADAPTER_VID;
deviceInfo->usbNetAdapter.pid = USB_NET_ADAPTER_PID;
}
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}

View File

@ -25,6 +25,7 @@
/* Includes ------------------------------------------------------------------*/
#include <dji_logger.h>
#include "hal_uart.h"
#include "utils/dji_config_manager.h"
/* Private constants ---------------------------------------------------------*/
#define UART_DEV_NAME_STR_SIZE (128)
@ -48,20 +49,32 @@ T_DjiReturnCode HalUart_Init(E_DjiHalUartNum uartNum, uint32_t baudRate, T_DjiUa
struct flock lock;
T_DjiReturnCode returnCode = DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
char uartName[UART_DEV_NAME_STR_SIZE];
char uart1Name[UART_DEV_NAME_STR_SIZE];
char uart2Name[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;
T_DjiUserLinkConfig linkConfig = {0};
uartHandleStruct = malloc(sizeof(T_UartHandleStruct));
if (uartHandleStruct == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_MEMORY_ALLOC_FAILED;
}
if (DjiUserConfigManager_IsEnable()) {
DjiUserConfigManager_GetLinkConfig(&linkConfig);
strcpy(uart1Name, linkConfig.uartConfig.uart1DeviceName);
strcpy(uart2Name, linkConfig.uartConfig.uart2DeviceName);
} else {
strcpy(uart1Name, LINUX_UART_DEV1);
strcpy(uart2Name, LINUX_UART_DEV2);
}
if (uartNum == DJI_HAL_UART_NUM_0) {
strcpy(uartName, LINUX_UART_DEV1);
strcpy(uartName, uart1Name);
} else if (uartNum == DJI_HAL_UART_NUM_1) {
strcpy(uartName, LINUX_UART_DEV2);
strcpy(uartName, uart2Name);
} else {
goto free_uart_handle;
}
@ -88,7 +101,7 @@ T_DjiReturnCode HalUart_Init(E_DjiHalUartNum uartNum, uint32_t baudRate, T_DjiUa
sprintf(systemCmd, "chmod 777 %s", uartName);
fp = popen(systemCmd, "r");
if (fp == NULL) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
goto free_uart_handle;
}
#endif
@ -244,10 +257,17 @@ T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint3
T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *status)
{
T_DjiUserLinkConfig linkConfig = {0};
if (uartNum == DJI_HAL_UART_NUM_0) {
status->isConnect = true;
} else if (uartNum == DJI_HAL_UART_NUM_1) {
status->isConnect = true;
if (DjiUserConfigManager_IsEnable()) {
DjiUserConfigManager_GetLinkConfig(&linkConfig);
status->isConnect = linkConfig.uartConfig.uart2DeviceEnable;
} else {
status->isConnect = true;
}
} else {
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}

View File

@ -25,6 +25,7 @@
/* Includes ------------------------------------------------------------------*/
#include "hal_usb_bulk.h"
#include "dji_logger.h"
#include "utils/dji_config_manager.h"
/* Private constants ---------------------------------------------------------*/
#define LINUX_USB_BULK_TRANSFER_TIMEOUT_MS (50)
@ -52,6 +53,13 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan
{
int32_t ret;
struct libusb_device_handle *handle = NULL;
T_DjiUserLinkConfig linkConfig = {0};
char usbBulk1EpInFd[USER_DEVICE_NAME_STR_MAX_SIZE];
char usbBulk1EpOutFd[USER_DEVICE_NAME_STR_MAX_SIZE];
char usbBulk2EpInFd[USER_DEVICE_NAME_STR_MAX_SIZE];
char usbBulk2EpOutFd[USER_DEVICE_NAME_STR_MAX_SIZE];
uint8_t usbBulk1InterfaceNum;
uint8_t usbBulk2InterfaceNum;
*usbBulkHandle = malloc(sizeof(T_HalUsbBulkObj));
if (*usbBulkHandle == NULL) {
@ -67,7 +75,7 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan
}
handle = libusb_open_device_with_vid_pid(NULL, usbBulkInfo.vid, usbBulkInfo.pid);
if(handle == NULL) {
if (handle == NULL) {
USER_LOG_ERROR("open usb device failed");
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
@ -87,23 +95,44 @@ T_DjiReturnCode HalUsbBulk_Init(T_DjiHalUsbBulkInfo usbBulkInfo, T_DjiUsbBulkHan
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_OUT_FD, O_RDWR);
if (DjiUserConfigManager_IsEnable()) {
DjiUserConfigManager_GetLinkConfig(&linkConfig);
usbBulk1InterfaceNum = linkConfig.usbBulkConfig.usbBulk1InterfaceNum;
usbBulk2InterfaceNum = linkConfig.usbBulkConfig.usbBulk2InterfaceNum;
snprintf(usbBulk1EpOutFd, sizeof(usbBulk1EpOutFd), "%s/ep1",
linkConfig.usbBulkConfig.usbBulk1DeviceName);
snprintf(usbBulk1EpInFd, sizeof(usbBulk1EpInFd), "%s/ep2",
linkConfig.usbBulkConfig.usbBulk1DeviceName);
snprintf(usbBulk2EpOutFd, sizeof(usbBulk2EpOutFd), "%s/ep1",
linkConfig.usbBulkConfig.usbBulk2DeviceName);
snprintf(usbBulk2EpInFd, sizeof(usbBulk2EpInFd), "%s/ep2",
linkConfig.usbBulkConfig.usbBulk2DeviceName);
} else {
usbBulk1InterfaceNum = LINUX_USB_BULK1_INTERFACE_NUM;
usbBulk2InterfaceNum = LINUX_USB_BULK2_INTERFACE_NUM;
strcpy(usbBulk1EpInFd, LINUX_USB_BULK1_EP_IN_FD);
strcpy(usbBulk1EpOutFd, LINUX_USB_BULK1_EP_OUT_FD);
strcpy(usbBulk2EpInFd, LINUX_USB_BULK2_EP_IN_FD);
strcpy(usbBulk2EpOutFd, LINUX_USB_BULK2_EP_OUT_FD);
}
if (usbBulkInfo.channelInfo.interfaceNum == usbBulk1InterfaceNum) {
((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(usbBulk1EpOutFd, O_RDWR);
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK1_EP_IN_FD, O_RDWR);
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(usbBulk1EpInFd, O_RDWR);
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
} else if (usbBulkInfo.channelInfo.interfaceNum == LINUX_USB_BULK2_INTERFACE_NUM) {
((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(LINUX_USB_BULK2_EP_OUT_FD, O_RDWR);
} else if (usbBulkInfo.channelInfo.interfaceNum == usbBulk2InterfaceNum) {
((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 = open(usbBulk2EpOutFd, O_RDWR);
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep1 < 0) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(LINUX_USB_BULK2_EP_IN_FD, O_RDWR);
((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 = open(usbBulk2EpInFd, O_RDWR);
if (((T_HalUsbBulkObj *) *usbBulkHandle)->ep2 < 0) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
@ -127,8 +156,9 @@ T_DjiReturnCode HalUsbBulk_DeInit(T_DjiUsbBulkHandle usbBulkHandle)
if (((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.isUsbHost == true) {
#ifdef LIBUSB_INSTALLED
ret = libusb_release_interface(handle, ((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum);
if(ret != 0) {
ret = libusb_release_interface(handle,
((T_HalUsbBulkObj *) usbBulkHandle)->usbBulkInfo.channelInfo.interfaceNum);
if (ret != 0) {
USER_LOG_ERROR("release usb bulk interface failed, errno = %d", ret);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
@ -208,19 +238,39 @@ T_DjiReturnCode HalUsbBulk_ReadData(T_DjiUsbBulkHandle usbBulkHandle, uint8_t *b
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;
T_DjiUserLinkConfig linkConfig = {0};
// 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;
if (DjiUserConfigManager_IsEnable()) {
DjiUserConfigManager_GetLinkConfig(&linkConfig);
// 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;
//attention: this interface only be called in usb device mode.
deviceInfo->vid = linkConfig.usbBulkConfig.usbDeviceVid;
deviceInfo->pid = linkConfig.usbBulkConfig.usbDevicePid;
// 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 = linkConfig.usbBulkConfig.usbBulk1InterfaceNum;
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].endPointIn = linkConfig.usbBulkConfig.usbBulk1EndpointIn;
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_0].endPointOut = linkConfig.usbBulkConfig.usbBulk1EndpointOut;
// This bulk channel is used to obtain DJI perception image and download camera media file.
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].interfaceNum = linkConfig.usbBulkConfig.usbBulk2InterfaceNum;
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointIn = linkConfig.usbBulkConfig.usbBulk2EndpointIn;
deviceInfo->channelInfo[DJI_HAL_USB_BULK_NUM_1].endPointOut = linkConfig.usbBulkConfig.usbBulk2EndpointOut;
} else {
//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;
}
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}

View 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)

View File

@ -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 DJIs 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(&currentTime);
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****/

View 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 DJIs 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******/

View 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 DJIs 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******/

View 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 DJIs 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******/

View File

@ -0,0 +1,151 @@
/**
********************************************************************
* @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 DJIs 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 "liveview/test_liveview.h"
#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;
E_DjiMountPosition mountPosition = DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1;
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"
<< "| [n] Run H.264 liveview sample - save H.264 files in the current directory |\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 'n':
DjiTest_LiveviewRunSample(mountPosition);
break;
case 'q':
break;
default:
break;
}
osalHandler->TaskSleepMs(2000);
goto start;
}
/* Private functions definition-----------------------------------------------*/
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/

View 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 DJIs 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****/

View 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 DJIs 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******/

View File

@ -22,8 +22,11 @@ include_directories(../nvidia_jetson/application)
file(GLOB_RECURSE MODULE_SAMPLE_SRC
../../../module_sample/liveview/*.c*
../../../module_sample/camera_manager/*.c*
../../../module_sample/hms_manager/*.c*
../../../module_sample/perception/*.c*
../../../module_sample/gimbal/*.c*
../../../module_sample/flight_controller/*.c*
../../../module_sample/hms_manager/*.c*
../../../../sample_c/module_sample/*.c
)
file(GLOB_RECURSE MODULE_COMMON_SRC ../common/*.c*)
@ -31,7 +34,7 @@ file(GLOB_RECURSE MODULE_HAL_SRC hal/*.c*)
file(GLOB_RECURSE MODULE_APP_SRC application/*.c*)
set(TOOLCHAIN_NAME aarch64-linux-gnu-gcc)
add_definitions(-DPLATFORM_ARCH_aarch64=1)
add_definitions(-DPLATFORM_ARCH_AARCH64=1)
add_definitions(-DSYSTEM_ARCH_LINUX=1)
set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/../common/3rdparty)
@ -45,92 +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)
execute_process(COMMAND opencv_version OUTPUT_VARIABLE OPENCV_VERSION)
if (${OPENCV_VERSION} STRLESS "4.0.0")
add_definitions(-DOPEN_CV_VERSION_3)
else ()
add_definitions(-DOPEN_CV_VERSION_4)
endif ()
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_psdk_libput
OUTPUT_STRIP_TRAILING_WHITESPACE
)
string(REGEX MATCH "version.*Copyright" ffmpeg_version_line ${ffmpeg_version_psdk_libput})
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_custom_command(TARGET ${PROJECT_NAME}
PRE_LINK COMMAND cmake ..
WORKING_DIRECTORY ${CMAKE_BINARY_DIR})
target_include_directories(${PROJECT_NAME} PRIVATE ${OpenCV_INCLUDE_DIRS})
if (OpenCV_FOUND)
target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS})
endif ()

View File

@ -35,9 +35,9 @@
#include "../common/osal/osal.h"
#include "../common/osal/osal_fs.h"
#include "../common/osal/osal_socket.h"
#include "../manifold2/hal/hal_usb_bulk.h"
#include "../manifold2/hal/hal_uart.h"
#include "../manifold2/hal/hal_network.h"
#include "../hal/hal_usb_bulk.h"
#include "../hal/hal_uart.h"
#include "../hal/hal_network.h"
/* Private constants ---------------------------------------------------------*/
#define DJI_LOG_PATH "Logs/DJI"
@ -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;
@ -158,31 +159,50 @@ void Application::DjiUser_SetupEnvironment()
throw std::runtime_error("Register osal handler error.");
}
#if (CONFIG_HARDWARE_CONNECTION == DJI_USE_UART_AND_USB_BULK_DEVICE)
returnCode = DjiPlatform_RegHalUartHandler(&uartHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Register hal uart handler error.");
}
#if (CONFIG_HARDWARE_CONNECTION == DJI_USE_UART_AND_USB_BULK_DEVICE)
returnCode = DjiPlatform_RegHalUsbBulkHandler(&usbBulkHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Register hal usb bulk handler error.");
}
#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_UART_AND_NETWORK_DEVICE)
returnCode = DjiPlatform_RegHalUartHandler(&uartHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Register hal network handler error");
}
returnCode = DjiPlatform_RegHalNetworkHandler(&networkHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
throw std::runtime_error("Register hal network handler error");
}
#elif (CONFIG_HARDWARE_CONNECTION == DJI_USE_ONLY_UART)
/*!< Attention: Only use uart hardware connection.
*/
#endif
returnCode = DjiPlatform_RegHalUartHandler(&uartHandler);
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");
}
#endif
returnCode = DjiPlatform_RegFileSystemHandler(&fileSystemHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
@ -234,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");
@ -311,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;
}

View File

@ -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_UART_AND_NETWORK_DEVICE
#define CONFIG_HARDWARE_CONNECTION DJI_USE_ONLY_USB_BULK_DEVICE
/* Exported types ------------------------------------------------------------*/

View File

@ -25,12 +25,10 @@
/* 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 <hms/test_hms.h>
#include <waypoint_v2/test_waypoint_v2.h>
#include <waypoint_v3/test_waypoint_v3.h>
#include <gimbal_manager/test_gimbal_manager.h>
#include "application.hpp"
#include "fc_subscription/test_fc_subscription.h"
#include <gimbal_emu/test_payload_gimbal_emu.h>
@ -41,8 +39,11 @@
#include "widget/test_widget_speaker.h"
#include <power_management/test_power_management.h>
#include "data_transmission/test_data_transmission.h"
#include <camera_manager/test_camera_manager.h>
#include <flight_controller/test_flight_controller_entry.h>
#include <positioning/test_positioning.h>
#include <hms_manager/hms_manager_entry.h>
#include "camera_manager/test_camera_manager_entry.h"
#include <hms_manager/hms_manager_entry.h>
/* Private constants ---------------------------------------------------------*/
@ -51,8 +52,6 @@
/* Private values -------------------------------------------------------------*/
/* Private functions declaration ---------------------------------------------*/
static T_DjiReturnCode DjiTest_HighPowerApplyPinInit();
static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState);
/* Exported functions definition ---------------------------------------------*/
int main(int argc, char **argv)
@ -68,25 +67,15 @@ start:
<< "\n"
<< "| Available commands: |\n"
<< "| [0] Fc subscribe sample - subscribe quaternion and gps data |\n"
<< "| [1] Flight controller sample - take off landing |\n"
<< "| [2] Flight controller sample - take off position ctrl landing |\n"
<< "| [3] Flight controller sample - take off go home force landing |\n"
<< "| [4] Flight controller sample - take off velocity ctrl landing |\n"
<< "| [5] Flight controller sample - arrest flying |\n"
<< "| [6] Flight controller sample - set get parameters |\n"
<< "| [7] Hms info sample - get health manger system info |\n"
<< "| [8] Waypoint 2.0 sample - run airline mission by settings (only support on M300 RTK) |\n"
<< "| [9] Waypoint 3.0 sample - run airline mission by kmz file (not support on M300 RTK) |\n"
<< "| [a] Gimbal manager sample |\n"
<< "| [1] Flight controller sample - you can control flying by PSDK |\n"
<< "| [2] Hms info manager sample - get health manger system info by language |\n"
<< "| [a] Gimbal manager sample - you can control gimbal by PSDK |\n"
<< "| [c] Camera stream view sample - display the camera video stream |\n"
<< "| [d] Stereo vision view sample - display the stereo image |\n"
<< "| [e] Start camera all features sample - you can operate the camera on DJI Pilot |\n"
<< "| [f] Start gimbal all features sample - you can operate the gimbal on DJI Pilot |\n"
<< "| [g] Start widget all features sample - you can operate the widget on DJI Pilot |\n"
<< "| [h] Start widget speaker sample - you can operate the speaker on DJI Pilot2 |\n"
<< "| [i] Start power management sample - you will see notification when aircraft power off |\n"
<< "| [j] Start data transmission sample - you can send or recv custom data on MSDK demo |\n"
<< "| [k] Run camera manager sample - you can test camera's functions interactively |\n"
<< "| [e] Run camera manager sample - you can test camera's functions interactively |\n"
<< "| [f] Start rtk positioning sample - you can receive rtk rtcm data when rtk signal is ok |\n"
<< "| [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;
@ -95,7 +84,7 @@ start:
DjiTest_FcSubscriptionRunSample();
break;
case '1':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_LANDING);
DjiUser_RunFlightControllerSample();
break;
case '2':
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_POSITION_CTRL_LANDING);
@ -113,13 +102,13 @@ start:
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SET_GET_PARAM);
break;
case '7':
DjiTest_HmsRunSample();
DjiUser_RunHmsManagerSample();
break;
case '8':
DjiTest_WaypointV2RunSample();
// DjiTest_WaypointV2RunSample();
break;
case '9':
DjiTest_WaypointV3RunSample();
// DjiTest_WaypointV3RunSample();
break;
case 'a':
DjiUser_RunGimbalManagerSample();
@ -131,77 +120,22 @@ start:
DjiUser_RunStereoVisionViewSample();
break;
case 'e':
returnCode = DjiTest_CameraEmuBaseStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("camera emu common init error");
break;
}
if (DjiPlatform_GetSocketHandler() != nullptr) {
returnCode = DjiTest_CameraEmuMediaStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("camera emu media init error");
break;
}
}
USER_LOG_INFO("Start camera all feautes sample successfully");
DjiUser_RunCameraManagerSample();
break;
case 'f':
if (DjiTest_GimbalStartService() != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("psdk gimbal init error");
returnCode = DjiTest_PositioningStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("rtk positioning sample init error");
break;
}
USER_LOG_INFO("Start gimbal all feautes sample successfully");
USER_LOG_INFO("Start rtk positioning sample successfully");
break;
case 'g':
returnCode = DjiTest_WidgetStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("widget sample init error");
break;
}
USER_LOG_INFO("Start widget all feautes sample successfully");
DjiUser_RunLidarDataSubscriptionSample();
break;
case 'h':
returnCode = DjiTest_WidgetSpeakerStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("widget speaker test init error");
break;
}
USER_LOG_INFO("Start widget speaker sample successfully");
break;
case 'i':
applyHighPowerHandler.pinInit = DjiTest_HighPowerApplyPinInit;
applyHighPowerHandler.pinWrite = DjiTest_WriteHighPowerApplyPin;
returnCode = DjiTest_RegApplyHighPowerHandler(&applyHighPowerHandler);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("regsiter apply high power handler error");
break;
}
returnCode = DjiTest_PowerManagementStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("power management init error");
break;
}
USER_LOG_INFO("Start power management sample successfully");
break;
case 'j':
returnCode = DjiTest_DataTransmissionStartService();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("data transmission sample init error");
break;
}
USER_LOG_INFO("Start data transmission sample successfully");
break;
case 'k':
DjiUser_RunCameraManagerSample();
DjiUser_RunRadarDataSubscriptionSample();
break;
default:
break;
@ -213,15 +147,5 @@ start:
}
/* Private functions definition-----------------------------------------------*/
static T_DjiReturnCode DjiTest_HighPowerApplyPinInit()
{
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
static T_DjiReturnCode DjiTest_WriteHighPowerApplyPin(E_DjiPowerManagementPinState pinState)
{
//attention: please pull up the HWPR pin state by hardware.
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/

View File

@ -44,16 +44,27 @@ T_DjiReturnCode HalNetWork_Init(const char *ipAddr, const char *netMask, T_DjiNe
{
int32_t ret;
char cmdStr[LINUX_CMD_STR_MAX_SIZE];
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
int32_t routeIp[4] = {0};
int32_t genMask[4] = {0};
if (ipAddr == NULL || netMask == NULL) {
USER_LOG_ERROR("hal network config param error");
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
}
sscanf(ipAddr, "%d.%d.%d.%d", &routeIp[0], &routeIp[1], &routeIp[2], &routeIp[3]);
sscanf(netMask, "%d.%d.%d.%d", &genMask[0], &genMask[1], &genMask[2], &genMask[3]);
routeIp[0] &= genMask[0];
routeIp[1] &= genMask[1];
routeIp[2] &= genMask[2];
routeIp[3] &= genMask[3];
//Attention: need root permission to config ip addr and netmask.
memset(cmdStr, 0, sizeof(cmdStr));
snprintf(cmdStr, sizeof(cmdStr), "ifconfig %s up", LINUX_NETWORK_DEV);
USER_LOG_DEBUG("%s", cmdStr);
ret = system(cmdStr);
if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Can't open the network."
@ -63,14 +74,34 @@ T_DjiReturnCode HalNetWork_Init(const char *ipAddr, const char *netMask, T_DjiNe
}
snprintf(cmdStr, sizeof(cmdStr), "ifconfig %s %s netmask %s", LINUX_NETWORK_DEV, ipAddr, netMask);
USER_LOG_DEBUG("%s", cmdStr);
ret = system(cmdStr);
if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Can't config the ip address of network."
"Probably the program not execute with root permission."
"Please use the root permission to execute the program.");
USER_LOG_ERROR("cmd failed: %s", cmdStr);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
osalHandler->TaskSleepMs(50);
snprintf(cmdStr, sizeof(cmdStr), "ip route flush dev %s", LINUX_NETWORK_DEV);
USER_LOG_DEBUG("%s", cmdStr);
ret = system(cmdStr);
if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("cmd failed: %s", cmdStr);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
snprintf(cmdStr, sizeof(cmdStr), "route add -net %d.%d.%d.%d netmask %s dev %s",
routeIp[0], routeIp[1], routeIp[2], routeIp[3], netMask, LINUX_NETWORK_DEV);
USER_LOG_DEBUG("%s", cmdStr);
ret = system(cmdStr);
if (ret != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("cmd failed: %s", cmdStr);
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
}
osalHandler->TaskSleepMs(50);
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}

View File

@ -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****/

View 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
}

View File

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

View File

@ -52,26 +52,33 @@ extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
#define LINUX_USB_BULK1_EP_OUT_FD "/dev/usb-ffs/bulk1/ep1"
#define LINUX_USB_BULK1_EP_IN_FD "/dev/usb-ffs/bulk1/ep2"
#define LINUX_USB_BULK1_EP_IN_FD "/dev/usb-ffs/bulk1/ep1"
#define LINUX_USB_BULK1_EP_OUT_FD "/dev/usb-ffs/bulk1/ep2"
#define LINUX_USB_BULK1_INTERFACE_NUM (7)
#define LINUX_USB_BULK1_END_POINT_IN (0x88)
#define LINUX_USB_BULK1_END_POINT_OUT (5)
#define LINUX_USB_BULK1_INTERFACE_NUM (0)
#define LINUX_USB_BULK1_END_POINT_IN (0x81)
#define LINUX_USB_BULK1_END_POINT_OUT (0x01)
#define LINUX_USB_BULK2_EP_OUT_FD "/dev/usb-ffs/bulk2/ep1"
#define LINUX_USB_BULK2_EP_IN_FD "/dev/usb-ffs/bulk2/ep2"
#define LINUX_USB_BULK2_EP_IN_FD "/dev/usb-ffs/bulk2/ep1"
#define LINUX_USB_BULK2_EP_OUT_FD "/dev/usb-ffs/bulk2/ep2"
#define LINUX_USB_BULK2_INTERFACE_NUM (8)
#define LINUX_USB_BULK2_END_POINT_IN (0x89)
#define LINUX_USB_BULK2_END_POINT_OUT (6)
#define LINUX_USB_BULK2_INTERFACE_NUM (1)
#define LINUX_USB_BULK2_END_POINT_IN (0x82)
#define LINUX_USB_BULK2_END_POINT_OUT (0x02)
#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 ------------------------------------------------------------*/

View 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 ()

View File

@ -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 DJIs 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(&currentTime);
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****/

View 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 DJIs 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******/

View 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 DJIs 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******/

View 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 DJIs 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******/

View 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 DJIs 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****/

View 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 DJIs 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****/

View 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 DJIs 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******/

View 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 DJIs 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****/

View 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 DJIs 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******/

View 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 DJIs 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****/

View 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 DJIs 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******/

View 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 DJIs 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****/

View 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 DJIs 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******/

View File

@ -155,7 +155,7 @@ T_DjiReturnCode DjiMediaFile_GetMediaFileAttr(T_DjiMediaFileHandle mediaFileHand
}
T_DjiReturnCode DjiMediaFile_GetDataOrg(struct _DjiMediaFile *mediaFileHandle, uint32_t offset, uint16_t len,
uint8_t *data, uint16_t *realLen)
uint8_t *data, uint32_t *realLen)
{
if (mediaFileHandle->mediaFileOptItem.getDataOrgFunc == NULL) {
USER_LOG_ERROR("Media file handle getDataOrgFunc null error");

View File

@ -57,7 +57,7 @@ typedef struct {
T_DjiReturnCode (*getAttrFunc)(struct _DjiMediaFile *mediaFileHandle, T_DjiCameraMediaFileAttr *mediaFileAttr);
T_DjiReturnCode (*getDataOrgFunc)(struct _DjiMediaFile *mediaFileHandle, uint32_t offset, uint16_t len,
uint8_t *data, uint16_t *realLen);
uint8_t *data, uint32_t *realLen);
T_DjiReturnCode (*getFileSizeOrgFunc)(struct _DjiMediaFile *mediaFileHandle, uint32_t *fileSize);
T_DjiReturnCode (*createThmFunc)(struct _DjiMediaFile *mediaFileHandle);
@ -91,7 +91,7 @@ T_DjiReturnCode DjiMediaFile_GetMediaFileAttr(T_DjiMediaFileHandle mediaFileHand
T_DjiCameraMediaFileAttr *mediaFileAttr);
T_DjiReturnCode DjiMediaFile_GetDataOrg(struct _DjiMediaFile *mediaFileHandle, uint32_t offset, uint16_t len,
uint8_t *data, uint16_t *realLen);
uint8_t *data, uint32_t *realLen);
T_DjiReturnCode DjiMediaFile_GetFileSizeOrg(struct _DjiMediaFile *mediaFileHandle, uint32_t *fileSize);
T_DjiReturnCode DjiMediaFile_CreateThm(T_DjiMediaFileHandle mediaFileHandle);

View File

@ -82,7 +82,7 @@ T_DjiReturnCode DjiMediaFile_GetAttrFunc_JPG(struct _DjiMediaFile *mediaFileHand
}
T_DjiReturnCode DjiMediaFile_GetDataOrigin_JPG(struct _DjiMediaFile *mediaFileHandle, uint32_t offset, uint16_t len,
uint8_t *data, uint16_t *realLen)
uint8_t *data, uint32_t *realLen)
{
return UtilFile_GetFileDataByPath(mediaFileHandle->filePath, offset, len, data, realLen);
}

View File

@ -49,7 +49,7 @@ T_DjiReturnCode DjiMediaFile_GetAttrFunc_JPG(struct _DjiMediaFile *mediaFileHand
T_DjiCameraMediaFileAttr *mediaFileAttr);
T_DjiReturnCode DjiMediaFile_GetDataOrigin_JPG(struct _DjiMediaFile *mediaFileHandle, uint32_t offset, uint16_t len,
uint8_t *data, uint16_t *realLen);
uint8_t *data, uint32_t *realLen);
T_DjiReturnCode DjiMediaFile_GetFileSizeOrigin_JPG(struct _DjiMediaFile *mediaFileHandle, uint32_t *fileSize);
T_DjiReturnCode DjiMediaFile_CreateThumbNail_JPG(struct _DjiMediaFile *mediaFileHandle);

View File

@ -115,7 +115,7 @@ out:
}
T_DjiReturnCode DjiMediaFile_GetDataOrigin_MP4(struct _DjiMediaFile *mediaFileHandle, uint32_t offset, uint16_t len,
uint8_t *data, uint16_t *realLen)
uint8_t *data, uint32_t *realLen)
{
return UtilFile_GetFileDataByPath(mediaFileHandle->filePath, offset, len, data, realLen);
}

View File

@ -49,7 +49,7 @@ T_DjiReturnCode DjiMediaFile_GetAttrFunc_MP4(struct _DjiMediaFile *mediaFileHand
T_DjiCameraMediaFileAttr *mediaFileAttr);
T_DjiReturnCode DjiMediaFile_GetDataOrigin_MP4(struct _DjiMediaFile *mediaFileHandle, uint32_t offset, uint16_t len,
uint8_t *data, uint16_t *realLen);
uint8_t *data, uint32_t *realLen);
T_DjiReturnCode DjiMediaFile_GetFileSizeOrigin_MP4(struct _DjiMediaFile *mediaFileHandle, uint32_t *fileSize);
T_DjiReturnCode DjiMediaFile_CreateThumbNail_MP4(struct _DjiMediaFile *mediaFileHandle);

View 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;
static int sockfd;
static struct sockaddr_in server;
@ -222,6 +224,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) {
@ -252,6 +255,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);
@ -284,6 +288,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);
@ -307,6 +312,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) {
@ -317,6 +323,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);
@ -340,6 +347,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;
@ -456,8 +464,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);
@ -929,6 +938,8 @@ static T_DjiReturnCode DjiTest_CameraRotationGimbal(T_TestCameraGimbalRotationAr
}
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);
@ -967,6 +978,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);
@ -1164,8 +1176,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);
@ -1174,13 +1185,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) {
@ -1189,10 +1208,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)) {
@ -1200,13 +1225,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;
@ -1214,8 +1240,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--;
}
}

View File

@ -23,6 +23,7 @@
*/
/* Includes ------------------------------------------------------------------*/
#include <errno.h>
#include <fcntl.h>
#include <stdlib.h>
#include "dji_logger.h"
@ -132,6 +133,7 @@ static T_DjiPlaybackInfo s_playbackInfo = {0};//非常重要的变量!!!!!!!!!!!
static T_DjiTaskHandle s_userSendVideoThread;
static T_UtilBuffer s_mediaPlayCommandBufferHandler = {0};//非常重要的变量,用户自定义功能读取此变量中的命令执行相应的操作!!!!!!!!!!!!!!!!!!!
static T_DjiMutexHandle s_mediaPlayCommandBufferMutex = {0};
static T_DjiSemaHandle s_mediaPlayWorkSem = NULL;
static uint8_t s_mediaPlayCommandBuffer[sizeof(T_TestPayloadCameraPlaybackCommand) * 32] = {0};
static const char *s_frameKeyChar = "[PACKET]";
static const char *s_frameDurationTimeKeyChar = "duration_time";
@ -190,6 +192,11 @@ T_DjiReturnCode DjiTest_CameraEmuMediaStartService(void)
s_psdkCameraMedia.StartDownloadNotification = StartDownloadNotification;
s_psdkCameraMedia.StopDownloadNotification = StopDownloadNotification;
if (DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS != osalHandler->SemaphoreCreate(0, &s_mediaPlayWorkSem)) {
USER_LOG_ERROR("SemaphoreCreate(\"%s\") error.", "s_mediaPlayWorkSem");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
if (osalHandler->MutexCreate(&s_mediaPlayCommandBufferMutex) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("mutex create error");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
@ -199,7 +206,8 @@ T_DjiReturnCode DjiTest_CameraEmuMediaStartService(void)
// 注册相机类负载设备的下载回放功能
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.");
@ -327,6 +335,7 @@ static T_DjiReturnCode DjiPlayback_PausePlay(T_DjiPlaybackInfo *playbackInfo)
USER_LOG_ERROR("mutex unlock error");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
osalHandler->SemaphorePost(s_mediaPlayWorkSem);
}
playbackInfo->isInPlayProcess = 0;
@ -511,7 +520,7 @@ static T_DjiReturnCode DjiPlayback_StartPlayProcess(const char *filePath, uint32
USER_LOG_ERROR("mutex unlock error");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
osalHandler->SemaphorePost(s_mediaPlayWorkSem);
return returnCode;
}
@ -540,7 +549,7 @@ static T_DjiReturnCode DjiPlayback_StopPlayProcess(void)
USER_LOG_ERROR("mutex unlock error");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
osalHandler->SemaphorePost(s_mediaPlayWorkSem);
return returnCode;
}
@ -751,7 +760,7 @@ static T_DjiReturnCode DjiPlayback_GetFrameRateOfVideoFile(const char *path, flo
ret = fscanf(fpCommand, "r_frame_rate=%d/%d", &frameRateMolecule, &frameRateDenominator);
if (ret <= 0) {
USER_LOG_ERROR("can not find frame rate.");
USER_LOG_ERROR("can not find frame rate form \"%s\".", path);
returnCode = DJI_ERROR_SYSTEM_MODULE_CODE_NOT_FOUND;
goto out;
}
@ -802,7 +811,7 @@ static T_DjiReturnCode GetMediaFileDir(char *dirPath)
static T_DjiReturnCode GetMediaFileOriginData(const char *filePath, uint32_t offset, uint32_t length, uint8_t *data)
{
T_DjiReturnCode returnCode;
uint16_t realLen = 0;
uint32_t realLen = 0;
T_DjiMediaFileHandle mediaFileHandle;
returnCode = DjiMediaFile_CreateHandle(filePath, &mediaFileHandle);
@ -1198,6 +1207,9 @@ static void *UserCameraMedia_SendVideoTask(void *arg)
char *videoFilePath = NULL;
char *transcodedFilePath = NULL;//转换视频编码后的文件路径
float frameRate = 1.0f;
uint32_t waitDuration = 1000 / SEND_VIDEO_TASK_FREQ;
uint32_t rightNow = 0;
uint32_t sendExpect = 0;
T_TestPayloadCameraVideoFrameInfo *frameInfo = NULL;//时长,大小,此帧在文件中的位置
uint32_t frameNumber = 0;
uint32_t frameCount = 0;
@ -1221,7 +1233,7 @@ static void *UserCameraMedia_SendVideoTask(void *arg)
exit(1);
}
if (s_isMediaFileDirPathConfigured == true) {
snprintf(tempPath, DJI_FILE_PATH_SIZE_MAX, "%sPSDK_0005.h264", s_mediaFileDirPath);
snprintf(tempPath, DJI_FILE_PATH_SIZE_MAX, "%smedia_file/PSDK_0005.h264", s_mediaFileDirPath);
} else {
snprintf(tempPath, DJI_FILE_PATH_SIZE_MAX, "%smedia_file/PSDK_0005.h264", curFileDirPath);
}
@ -1255,8 +1267,16 @@ static void *UserCameraMedia_SendVideoTask(void *arg)
int frameNumberSendCounter=0;
(void)osalHandler->GetTimeMs(&rightNow);
sendExpect = rightNow + waitDuration;
while (1) {
osalHandler->TaskSleepMs(1000 / SEND_VIDEO_TASK_FREQ);
(void)osalHandler->GetTimeMs(&rightNow);
if (sendExpect > rightNow) {
waitDuration = sendExpect - rightNow;
} else {
waitDuration = 1000 / SEND_VIDEO_TASK_FREQ;
}
(void)osalHandler->SemaphoreTimedWait(s_mediaPlayWorkSem, waitDuration);
// response playback command
if (osalHandler->MutexLock(s_mediaPlayCommandBufferMutex) != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
@ -1335,13 +1355,13 @@ static void *UserCameraMedia_SendVideoTask(void *arg)
fpFile = fopen(transcodedFilePath, "rb+");//打开编码后的文件
if (fpFile == NULL) {
USER_LOG_ERROR("open video file fail.111111111111111111111111");
USER_LOG_ERROR("open video file:\"%s\" fail:%d.", transcodedFilePath, errno);
continue;
}
send:
if (fpFile == NULL) {
USER_LOG_ERROR("open video file fail.222222222222222222222222222");
USER_LOG_ERROR("open video file fail.");
continue;
}
@ -1363,16 +1383,10 @@ send:
continue;
}
//????????????????????????????????
if (!USER_UTIL_IS_WORK_TURN(sendVideoStep++, frameRate, SEND_VIDEO_TASK_FREQ))
continue;
//3. 解析视频流文件
//基于PSDK 开发的相机类负载设备获取视频流文件的信息后,将解析视频流文件的内容,识别视频流文件的帧头。
frameBufSize = frameInfo[frameNumber].size;//这行几行代码的意思:每一帧的大小不一样
printf("第 %d 帧大小:%d\n", frameNumberSendCounter, frameBufSize);
frameNumberSendCounter++;
if (videoStreamType == DJI_CAMERA_VIDEO_STREAM_TYPE_H264_DJI_FORMAT) {
frameBufSize = frameBufSize + VIDEO_FRAME_AUD_LEN;
}
@ -1406,7 +1420,7 @@ send:
// for(int i=0;i<dataLength - VIDEO_FRAME_AUD_LEN;i++)
// {
//// printf("%c",data[i]);
// //printf("%c",data[i]);
// printf("%02X ",dataBuffer[i]);
// }
// printf("\n");
@ -1423,6 +1437,9 @@ send:
lengthOfDataHaveBeenSent += lengthOfDataToBeSent;
}
(void)osalHandler->GetTimeMs(&sendExpect);
sendExpect += (1000 / frameRate);
if ((frameNumber++) >= frameCount) {
USER_LOG_DEBUG("reach file tail.");
frameNumber = 0;
@ -1436,10 +1453,10 @@ send:
returnCode = DjiPayloadCamera_GetVideoStreamState(&videoStreamState);
if (returnCode == DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_DEBUG(
"video stream state: realtimeBandwidthLimit: %d, realtimeBandwidthBeforeFlowController: %d, realtimeBandwidthAfterFlowController:%d busyState: %d.",
videoStreamState.realtimeBandwidthLimit, videoStreamState.realtimeBandwidthBeforeFlowController,
videoStreamState.realtimeBandwidthAfterFlowController,
videoStreamState.busyState);
"video stream state: realtimeBandwidthLimit: %d, realtimeBandwidthBeforeFlowController: %d, realtimeBandwidthAfterFlowController:%d busyState: %d.",
videoStreamState.realtimeBandwidthLimit, videoStreamState.realtimeBandwidthBeforeFlowController,
videoStreamState.realtimeBandwidthAfterFlowController,
videoStreamState.busyState);
} else {
USER_LOG_ERROR("get video stream state error.");
}

View File

@ -47,7 +47,6 @@ typedef enum {
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_TAP_ZOOM_POINT,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAMERA_ZOOM_PARAM,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_SINGLE_PHOTO,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_AEB_PHOTO,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_BURST_PHOTO,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOOT_INTERVAL_PHOTO,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_RECORD_VIDEO,
@ -56,6 +55,23 @@ typedef enum {
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_THERMOMETRY,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_GET_LIDAR_RANGING_INFO,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_IR_CAMERA_ZOOM_PARAM,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_NIGHT_SCENE_MODE,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_CAPTURE_RECORDING_STREAMS,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SHOW_STORAGE_INFO,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_FORMAT_SD_CARD,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_LINK_ZOOM,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_USER_CUSTOM_DIR_FILE_NAME,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_RESET_CAMERA_SETTINGS,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_AE_LOCK_MODE,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_FOCUS_RING_VALUE,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_CONNECT_STATUS_TEST,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_GET_PHOTO_VIDEO_PARAM,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_METERING_MODE,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_METERING_POINT,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_FFC_MODE_AND_TRRIGER,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SET_GAIN_MODE,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_GET_CAMERA_STATUS,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_SUBSCRIBE_POINT_CLOUD,
E_DJI_TEST_CAMERA_MANAGER_SAMPLE_SELECT_INDEX_MAX
} E_DjiTestCameraManagerSampleSelect;
/* Exported functions --------------------------------------------------------*/
@ -206,18 +222,6 @@ T_DjiReturnCode DjiTest_CameraManagerStartShootSinglePhoto(E_DjiMountPosition po
T_DjiReturnCode DjiTest_CameraManagerStartShootBurstPhoto(E_DjiMountPosition position,
E_DjiCameraBurstCount burstCount);
/*! @brief Sample to shoot AEB photo, using async api
*
* @note In this interface, camera will be set to be the SHOOT_PHOTO mode
* then start to shoot a AEB photo.
* @param index payload node index, input limit see enum
* DJI::OSDK::PayloadIndexType
* @param photoNum The number of pictures in each AEB shooting
* @return T_DjiReturnCode error code
*/
T_DjiReturnCode DjiTest_CameraManagerStartShootAEBPhoto(E_DjiMountPosition position,
E_DjiCameraManagerPhotoAEBCount aebCount);
/*! @brief Sample to start shooting interval photo, using async api
*
* @note In this interface, camera will be set to be the SHOOT_PHOTO mode

View File

@ -0,0 +1,98 @@
/**
********************************************************************
* @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 DJIs 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 = DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
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****/

View 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 DJIs 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******/

View File

@ -42,8 +42,12 @@
/* Private functions declaration ---------------------------------------------*/
static void *UserDataTransmission_Task(void *arg);
static T_DjiReturnCode ReceiveDataFromMobile(const uint8_t *data, uint16_t len);
static T_DjiReturnCode ReceiveDataFromOnboardComputer(const uint8_t *data, uint16_t len);
static T_DjiReturnCode ReceiveDataFromCloud(const uint8_t *data, uint16_t len);
static T_DjiReturnCode ReceiveDataFromExtensionPort(const uint8_t *data, uint16_t len);
static T_DjiReturnCode ReceiveDataFromPayload(const uint8_t *data, uint16_t len);
static T_DjiReturnCode ReceiveDataFromPayload1(const uint8_t *data, uint16_t len);
static T_DjiReturnCode ReceiveDataFromPayload2(const uint8_t *data, uint16_t len);
static T_DjiReturnCode ReceiveDataFromPayload3(const uint8_t *data, uint16_t len);
/* Private variables ---------------------------------------------------------*/
static T_DjiTaskHandle s_userDataTransmissionThread;//线程句柄
@ -80,13 +84,31 @@ T_DjiReturnCode DjiTest_DataTransmissionStartService(void)
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
if (s_aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_PAYLOAD_PORT_NO1 ||
if ((s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30 ||
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_M4TD) &&
s_aircraftInfoBaseInfo.mountPositionType != DJI_MOUNT_POSITION_TYPE_MANIFOLD3_ONBOARD) {
channelAddress = DJI_CHANNEL_ADDRESS_CLOUD_API;
djiStat = DjiLowSpeedDataChannel_RegRecvDataCallback(channelAddress, ReceiveDataFromCloud);
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("register receive data from cloud error.");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
}
if (s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M400) {
USER_LOG_INFO("Only supports small data transmission between PSDK and MSDK.");
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;
djiStat = DjiLowSpeedDataChannel_RegRecvDataCallback(channelAddress, ReceiveDataFromOnboardComputer);
djiStat = DjiLowSpeedDataChannel_RegRecvDataCallback(channelAddress, ReceiveDataFromExtensionPort);
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("register receive data from onboard coputer error.");
USER_LOG_ERROR("register receive data from extension port error.");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
@ -103,9 +125,24 @@ T_DjiReturnCode DjiTest_DataTransmissionStartService(void)
USER_LOG_ERROR("get data stream remote address error.");
}
} else if (s_aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_EXTENSION_PORT) {
} else if (s_aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_EXTENSION_PORT
|| DJI_MOUNT_POSITION_EXTENSION_LITE_PORT == s_aircraftInfoBaseInfo.mountPosition) {
channelAddress = DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO1;
djiStat = DjiLowSpeedDataChannel_RegRecvDataCallback(channelAddress, ReceiveDataFromPayload);
djiStat = DjiLowSpeedDataChannel_RegRecvDataCallback(channelAddress, ReceiveDataFromPayload1);
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("register receive data from payload NO1 error.");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
channelAddress = DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO2;
djiStat = DjiLowSpeedDataChannel_RegRecvDataCallback(channelAddress, ReceiveDataFromPayload2);
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("register receive data from payload NO1 error.");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
channelAddress = DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO3;
djiStat = DjiLowSpeedDataChannel_RegRecvDataCallback(channelAddress, ReceiveDataFromPayload3);
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("register receive data from payload NO1 error.");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
@ -154,7 +191,7 @@ T_DjiReturnCode DjiTest_DataTransmissionStopService(void)
static void *UserDataTransmission_Task(void *arg)
{
T_DjiReturnCode djiStat;
const uint8_t dataToBeSent[] = "DJI Data Transmission Test Data.\r\n";
const uint8_t dataToBeSent[] = "DJI Data Transmission Test Data.";
T_DjiDataChannelState state = {0};
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
E_DjiChannelAddress channelAddress;
@ -179,25 +216,48 @@ static void *UserDataTransmission_Task(void *arg)
USER_LOG_ERROR("get send to mobile channel state error.");
}
if (s_aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M30 ||
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_M4TD ) {
channelAddress = DJI_CHANNEL_ADDRESS_CLOUD_API;
djiStat = DjiLowSpeedDataChannel_SendData(channelAddress, dataToBeSent, sizeof(dataToBeSent));
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
USER_LOG_ERROR("send data to cloud error.");
djiStat = DjiLowSpeedDataChannel_GetSendDataState(channelAddress, &state);
if (djiStat == DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_DEBUG(
"send to cloud state: realtimeBandwidthBeforeFlowController: %d, realtimeBandwidthAfterFlowController: %d, busyState: %d.",
state.realtimeBandwidthBeforeFlowController, state.realtimeBandwidthAfterFlowController,
state.busyState);
} else {
USER_LOG_ERROR("get send to cloud channel state error.");
}
}
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;
djiStat = DjiLowSpeedDataChannel_SendData(channelAddress, dataToBeSent, sizeof(dataToBeSent));
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
USER_LOG_ERROR("send data to onboard computer error.");
USER_LOG_ERROR("send data to extension port error.");
djiStat = DjiLowSpeedDataChannel_GetSendDataState(channelAddress, &state);
if (djiStat == DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_DEBUG(
"send to onboard computer state: realtimeBandwidthBeforeFlowController: %d, realtimeBandwidthAfterFlowController: %d, busyState: %d.",
"send to extension port state: realtimeBandwidthBeforeFlowController: %d, realtimeBandwidthAfterFlowController: %d, busyState: %d.",
state.realtimeBandwidthBeforeFlowController, state.realtimeBandwidthAfterFlowController,
state.busyState);
} else {
USER_LOG_ERROR("get send to onboard computer channel state error.");
USER_LOG_ERROR("get send to extension port channel state error.");
}
if (DjiPlatform_GetSocketHandler() != NULL) {
#ifdef SYSTEM_ARCH_LINUX
djiStat = DjiHighSpeedDataChannel_SendDataStreamData(dataToBeSent, sizeof(dataToBeSent));
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
USER_LOG_ERROR("send data to data stream error.");
@ -210,21 +270,22 @@ static void *UserDataTransmission_Task(void *arg)
} else {
USER_LOG_ERROR("get data stream state error.");
}
#endif
}
} else if (s_aircraftInfoBaseInfo.mountPosition == DJI_MOUNT_POSITION_EXTENSION_PORT) {
channelAddress = DJI_CHANNEL_ADDRESS_PAYLOAD_PORT_NO1;
djiStat = DjiLowSpeedDataChannel_SendData(channelAddress, dataToBeSent, sizeof(dataToBeSent));
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
USER_LOG_ERROR("send data to onboard computer error.");
USER_LOG_ERROR("send data to extension port error.");
djiStat = DjiLowSpeedDataChannel_GetSendDataState(channelAddress, &state);
if (djiStat == DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_DEBUG(
"send to onboard computer state: realtimeBandwidthBeforeFlowController: %d, realtimeBandwidthAfterFlowController: %d, busyState: %d.",
"send to extension port state: realtimeBandwidthBeforeFlowController: %d, realtimeBandwidthAfterFlowController: %d, busyState: %d.",
state.realtimeBandwidthBeforeFlowController, state.realtimeBandwidthAfterFlowController,
state.busyState);
} else {
USER_LOG_ERROR("get send to onboard computer channel state error.");
USER_LOG_ERROR("get send to extension port channel state error.");
}
}
}
@ -255,7 +316,7 @@ static T_DjiReturnCode ReceiveDataFromMobile(const uint8_t *data, uint16_t len)
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
static T_DjiReturnCode ReceiveDataFromOnboardComputer(const uint8_t *data, uint16_t len)
static T_DjiReturnCode ReceiveDataFromCloud(const uint8_t *data, uint16_t len)
{
char *printData = NULL;
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
@ -268,7 +329,28 @@ static T_DjiReturnCode ReceiveDataFromOnboardComputer(const uint8_t *data, uint1
strncpy(printData, (const char *) data, len);
printData[len] = '\0';
USER_LOG_INFO("receive data from onboard computer: %s, len:%d.", printData, len);
USER_LOG_INFO("receive data from cloud: %s, len:%d.", printData, len);
DjiTest_WidgetLogAppend("receive data: %s, len:%d.", printData, len);
osalHandler->Free(printData);
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
static T_DjiReturnCode ReceiveDataFromExtensionPort(const uint8_t *data, uint16_t len)
{
char *printData = NULL;
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
printData = osalHandler->Malloc(len + 1);
if (printData == NULL) {
USER_LOG_ERROR("malloc memory for printData fail.");
return DJI_ERROR_SYSTEM_MODULE_CODE_MEMORY_ALLOC_FAILED;
}
strncpy(printData, (const char *) data, len);
printData[len] = '\0';
USER_LOG_INFO("receive data from extension port: %s, len:%d.", printData, len);
DjiTest_WidgetLogAppend("receive data: %s, len:%d.", printData, len);
osalHandler->Free(printData);
@ -297,4 +379,22 @@ static T_DjiReturnCode ReceiveDataFromPayload(const uint8_t *data, uint16_t len)
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
static T_DjiReturnCode ReceiveDataFromPayload1(const uint8_t *data, uint16_t len)
{
USER_LOG_INFO("Receive from payload on port 1");
return ReceiveDataFromPayload(data, len);
}
static T_DjiReturnCode ReceiveDataFromPayload2(const uint8_t *data, uint16_t len)
{
USER_LOG_INFO("Receive from payload on port 2");
return ReceiveDataFromPayload(data, len);
}
static T_DjiReturnCode ReceiveDataFromPayload3(const uint8_t *data, uint16_t len)
{
USER_LOG_INFO("Receive from payload on port 3");
return ReceiveDataFromPayload(data, len);
}
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/

View File

@ -32,7 +32,7 @@
/* Private constants ---------------------------------------------------------*/
#define FC_SUBSCRIPTION_TASK_FREQ (1)
#define FC_SUBSCRIPTION_TASK_STACK_SIZE (1024)
#define FC_SUBSCRIPTION_TASK_STACK_SIZE (2048)
/* Private types -------------------------------------------------------------*/
@ -168,9 +168,9 @@ T_DjiReturnCode DjiTest_FcSubscriptionRunSample(void)
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
USER_LOG_INFO("--> Step 3: Get latest value of the subscribed topics in the next 20 seconds\r\n");
USER_LOG_INFO("--> Step 3: Get latest value of the subscribed topics in the next 10 seconds\r\n");
for (int i = 0; i < 20; ++i) {
for (int i = 0; i < 10; ++i) {
osalHandler->TaskSleepMs(1000 / FC_SUBSCRIPTION_TASK_FREQ);
djiStat = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_VELOCITY,
(uint8_t *) &velocity,
@ -194,8 +194,8 @@ T_DjiReturnCode DjiTest_FcSubscriptionRunSample(void)
USER_LOG_INFO("gps position: x = %d y = %d z = %d.", gpsPosition.x, gpsPosition.y, gpsPosition.z);
}
//Attention: if you want to subscribe the single battery info on M300 RTK, you need connect USB cable to
//OSDK device or use topic DJI_FC_SUBSCRIPTION_TOPIC_BATTERY_INFO instead.
// Attention: if you want to subscribe the single battery info on M300 RTK, you need connect USB cable to
// OSDK device or use topic DJI_FC_SUBSCRIPTION_TOPIC_BATTERY_INFO instead.
djiStat = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_BATTERY_SINGLE_INFO_INDEX1,
(uint8_t *) &singleBatteryInfo,
sizeof(T_DjiFcSubscriptionSingleBatteryInfo),
@ -225,7 +225,26 @@ T_DjiReturnCode DjiTest_FcSubscriptionRunSample(void)
}
}
USER_LOG_INFO("--> Step 4: Deinit fc subscription module");
USER_LOG_INFO("--> Step 4: Unsubscribe the topics of quaternion, velocity and gps position");
djiStat = DjiFcSubscription_UnSubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_QUATERNION);
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("UnSubscribe topic quaternion error.");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
djiStat = DjiFcSubscription_UnSubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_VELOCITY);
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("UnSubscribe topic quaternion error.");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
djiStat = DjiFcSubscription_UnSubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_GPS_POSITION);
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("UnSubscribe topic quaternion error.");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
USER_LOG_INFO("--> Step 5: Deinit fc subscription module");
djiStat = DjiFcSubscription_DeInit();
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {

View File

@ -34,14 +34,6 @@
/* Private constants ---------------------------------------------------------*/
/* Private types -------------------------------------------------------------*/
#pragma pack(1)
typedef struct {
dji_f32_t x;
dji_f32_t y;
dji_f32_t z;
} T_DjiTestFlightControlVector3f; // pack(1)
#pragma pack()
typedef struct {
E_DjiFcSubscriptionDisplayMode displayMode;
char *displayModeStr;
@ -51,6 +43,8 @@ typedef struct {
static T_DjiOsalHandler *s_osalHandler = NULL;
static const double s_earthCenter = 6378137.0;
static const double s_degToRad = 0.01745329252;
static bool s_isFtsCallbackRegistered = false;
static int32_t s_ftsTriggerCount = 0;
static const T_DjiTestFlightControlDisplayModeStr s_flightControlDisplayModeStr[] = {
{.displayMode = DJI_FC_SUBSCRIPTION_DISPLAY_MODE_ATTITUDE, .displayModeStr = "attitude mode"},
@ -96,8 +90,6 @@ static bool DjiTest_FlightControlMoveByPositionOffset(T_DjiTestFlightControlVect
float yawDesiredInDeg,
float posThresholdInM,
float yawThresholdInDeg);
static void DjiTest_FlightControlVelocityAndYawRateCtrl(T_DjiTestFlightControlVector3f offsetDesired, float yawRate,
uint32_t timeMs);
static T_DjiReturnCode DjiTest_FlightControlInit(void);
static T_DjiReturnCode DjiTest_FlightControlDeInit(void);
static void DjiTest_FlightControlTakeOffLandingSample(void);
@ -105,6 +97,10 @@ static void DjiTest_FlightControlPositionControlSample(void);
static void DjiTest_FlightControlGoHomeForceLandingSample(void);
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);
/* Exported functions definition ---------------------------------------------*/
@ -138,11 +134,16 @@ T_DjiReturnCode DjiTest_FlightControlRunSample(E_DjiTestFlightCtrlSampleSelect f
T_DjiReturnCode DjiTest_FlightControlInit(void)
{
T_DjiReturnCode returnCode;
T_DjiFlightControllerRidInfo ridInfo = {0};
s_osalHandler = DjiPlatform_GetOsalHandler();
if (!s_osalHandler) return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
returnCode = DjiFlightController_Init();
ridInfo.latitude = 22.542812;
ridInfo.longitude = 113.958902;
ridInfo.altitude = 10;
returnCode = DjiFlightController_Init(ridInfo);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Init flight controller module failed, error code:0x%08llX", returnCode);
return returnCode;
@ -236,7 +237,7 @@ T_DjiReturnCode DjiTest_FlightControlDeInit(void)
{
T_DjiReturnCode returnCode;
returnCode = DjiFlightController_Deinit();
returnCode = DjiFlightController_DeInit();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Deinit flight controller module failed, error code:0x%08llX",
returnCode);
@ -325,25 +326,25 @@ void DjiTest_FlightControlPositionControlSample()
USER_LOG_INFO("Successful take off\r\n");
DjiTest_WidgetLogAppend("Successful take off\r\n");
USER_LOG_INFO("--> Step 3: Move to north:0(m), earth:6(m), up:6(m) , yaw:30(degree) from current point");
DjiTest_WidgetLogAppend("--> Step 3: Move to north:0(m), earth:6(m), up:6(m) , yaw:30(degree) from current point");
USER_LOG_INFO("--> Step 3: Move to north:0(m), east:6(m), up:6(m) , yaw:30(degree) from current point");
DjiTest_WidgetLogAppend("--> Step 3: Move to north:0(m), east:6(m), up:6(m) , yaw:30(degree) from current point");
if (!DjiTest_FlightControlMoveByPositionOffset((T_DjiTestFlightControlVector3f) {0, 6, 6}, 30, 0.8, 1)) {
USER_LOG_ERROR("Move to north:0(m), earth:6(m), up:6(m) , yaw:30(degree) from current point failed");
USER_LOG_ERROR("Move to north:0(m), east:6(m), up:6(m) , yaw:30(degree) from current point failed");
goto out;
};
USER_LOG_INFO("--> Step 4: Move to north:6(m), earth:0(m), up:-3(m) , yaw:-30(degree) from current point");
USER_LOG_INFO("--> Step 4: Move to north:6(m), east:0(m), up:-3(m) , yaw:-30(degree) from current point");
DjiTest_WidgetLogAppend(
"--> Step 4: Move to north:6(m), earth:0(m), up:-3(m) , yaw:-30(degree) from current point");
"--> Step 4: Move to north:6(m), east:0(m), up:-3(m) , yaw:-30(degree) from current point");
if (!DjiTest_FlightControlMoveByPositionOffset((T_DjiTestFlightControlVector3f) {6, 0, -3}, -30, 0.8, 1)) {
USER_LOG_ERROR("Move to north:6(m), earth:0(m), up:-3(m) , yaw:-30(degree) from current point failed");
USER_LOG_ERROR("Move to north:6(m), east:0(m), up:-3(m) , yaw:-30(degree) from current point failed");
goto out;
};
USER_LOG_INFO("--> Step 5: Move to north:-6(m), earth:-6(m), up:0(m) , yaw:0(degree) from current point");
DjiTest_WidgetLogAppend("--> Step 5: Move to north:-6(m), earth:-6(m), up:0(m) , yaw:0(degree) from current point");
USER_LOG_INFO("--> Step 5: Move to north:-6(m), east:-6(m), up:0(m) , yaw:0(degree) from current point");
DjiTest_WidgetLogAppend("--> Step 5: Move to north:-6(m), east:-6(m), up:0(m) , yaw:0(degree) from current point");
if (!DjiTest_FlightControlMoveByPositionOffset((T_DjiTestFlightControlVector3f) {-6, -6, 0}, 0, 0.8, 1)) {
USER_LOG_ERROR("Move to north:-6(m), earth:-6(m), up:0(m) , yaw:0(degree) from current point failed");
USER_LOG_ERROR("Move to north:-6(m), east:-6(m), up:0(m) , yaw:0(degree) from current point failed");
goto out;
}
@ -394,17 +395,17 @@ void DjiTest_FlightControlGoHomeForceLandingSample()
USER_LOG_INFO("Successful take off\r\n");
DjiTest_WidgetLogAppend("Successful take off\r\n");
USER_LOG_INFO("--> Step 3: Move to north:0(m), earth:0(m), up:30(m) , yaw:0(degree) from current point");
DjiTest_WidgetLogAppend("--> Step 3: Move to north:0(m), earth:0(m), up:30(m) , yaw:0(degree) from current point");
USER_LOG_INFO("--> Step 3: Move to north:0(m), east:0(m), up:30(m) , yaw:0(degree) from current point");
DjiTest_WidgetLogAppend("--> Step 3: Move to north:0(m), east:0(m), up:30(m) , yaw:0(degree) from current point");
if (!DjiTest_FlightControlMoveByPositionOffset((T_DjiTestFlightControlVector3f) {0, 0, 30}, 0, 0.8, 1)) {
USER_LOG_ERROR("Move to north:0(m), earth:0(m), up:30(m) , yaw:0(degree) from current point failed");
USER_LOG_ERROR("Move to north:0(m), east:0(m), up:30(m) , yaw:0(degree) from current point failed");
goto out;
}
USER_LOG_INFO("--> Step 4: Move to north:10(m), earth:0(m), up:0(m) , yaw:0(degree) from current point");
DjiTest_WidgetLogAppend("--> Step 4: Move to north:10(m), earth:0(m), up:0(m) , yaw:0(degree) from current point");
USER_LOG_INFO("--> Step 4: Move to north:10(m), east:0(m), up:0(m) , yaw:0(degree) from current point");
DjiTest_WidgetLogAppend("--> Step 4: Move to north:10(m), east:0(m), up:0(m) , yaw:0(degree) from current point");
if (!DjiTest_FlightControlMoveByPositionOffset((T_DjiTestFlightControlVector3f) {10, 0, 0}, 0, 0.8, 1)) {
USER_LOG_ERROR("Move to north:10(m), earth:0(m), up:0(m) , yaw:0(degree) from current point failed");
USER_LOG_ERROR("Move to north:10(m), east:0(m), up:0(m) , yaw:0(degree) from current point failed");
goto out;
}
@ -434,10 +435,10 @@ void DjiTest_FlightControlGoHomeForceLandingSample()
USER_LOG_INFO("Current go home altitude is %d m\r\n", goHomeAltitude);
DjiTest_WidgetLogAppend("Current go home altitude is %d m\r\n", goHomeAltitude);
USER_LOG_INFO("--> Step 7: Move to north:20(m), earth:0(m), up:0(m) , yaw:0(degree) from current point");
DjiTest_WidgetLogAppend("--> Step 7: Move to north:20(m), earth:0(m), up:0(m) , yaw:0(degree) from current point");
USER_LOG_INFO("--> Step 7: Move to north:20(m), east:0(m), up:0(m) , yaw:0(degree) from current point");
DjiTest_WidgetLogAppend("--> Step 7: Move to north:20(m), east:0(m), up:0(m) , yaw:0(degree) from current point");
if (!DjiTest_FlightControlMoveByPositionOffset((T_DjiTestFlightControlVector3f) {20, 0, 0}, 0, 0.8, 1)) {
USER_LOG_ERROR("Move to north:20(m), earth:0(m), up:0(m) , yaw:0(degree) from current point failed");
USER_LOG_ERROR("Move to north:20(m), east:0(m), up:0(m) , yaw:0(degree) from current point failed");
goto out;
}
@ -489,9 +490,9 @@ void DjiTest_FlightControlVelocityControlSample()
DjiTest_WidgetLogAppend("Successful take off\r\n");
USER_LOG_INFO(
"--> Step 3: Move with north:0(m/s), earth:0(m/s), up:5(m/s), yaw:0(deg/s) from current point for 2s!");
"--> Step 3: Move with north:0(m/s), east:0(m/s), up:5(m/s), yaw:0(deg/s) from current point for 2s!");
DjiTest_WidgetLogAppend(
"--> Step 3: Move with north:0(m/s), earth:0(m/s), up:5(m/s), yaw:0(deg/s) from current point for 2s!");
"--> Step 3: Move with north:0(m/s), east:0(m/s), up:5(m/s), yaw:0(deg/s) from current point for 2s!");
DjiTest_FlightControlVelocityAndYawRateCtrl((T_DjiTestFlightControlVector3f) {0, 0, 5.0}, 0, 2000);
USER_LOG_INFO("--> Step 4: Emergency brake for 2s");
@ -509,9 +510,9 @@ void DjiTest_FlightControlVelocityControlSample()
}
USER_LOG_INFO(
"--> Step 5: Move with north:-1.5(m/s), earth:2(m/s), up:0(m/s), yaw:20(deg/s) from current point for 2s!");
"--> Step 5: Move with north:-1.5(m/s), east:2(m/s), up:0(m/s), yaw:20(deg/s) from current point for 2s!");
DjiTest_WidgetLogAppend(
"--> Step 5: Move with north:-1.5(m/s), earth:2(m/s), up:0(m/s), yaw:20(deg/s) from current point for 2s!");
"--> Step 5: Move with north:-1.5(m/s), east:2(m/s), up:0(m/s), yaw:20(deg/s) from current point for 2s!");
DjiTest_FlightControlVelocityAndYawRateCtrl((T_DjiTestFlightControlVector3f) {-1.5, 2, 0}, 20, 2000);
USER_LOG_INFO("--> Step 6: Emergency brake for 2s");
@ -529,9 +530,9 @@ void DjiTest_FlightControlVelocityControlSample()
}
USER_LOG_INFO(
"--> Step 7: Move with north:3(m/s), earth:0(m/s), up:0(m/s), yaw:0(deg/s) from current point for 2.5s!");
"--> Step 7: Move with north:3(m/s), east:0(m/s), up:0(m/s), yaw:0(deg/s) from current point for 2.5s!");
DjiTest_WidgetLogAppend(
"--> Step 7: Move with north:3(m/s), earth:0(m/s), up:0(m/s), yaw:0(deg/s) from current point for 2.5s!");
"--> Step 7: Move with north:3(m/s), east:0(m/s), up:0(m/s), yaw:0(deg/s) from current point for 2.5s!");
DjiTest_FlightControlVelocityAndYawRateCtrl((T_DjiTestFlightControlVector3f) {3, 0, 0}, 0, 2500);
USER_LOG_INFO("--> Step 8: Emergency brake for 2s");
@ -549,9 +550,9 @@ void DjiTest_FlightControlVelocityControlSample()
}
USER_LOG_INFO(
"--> Step 9: Move with north:-1.6(m/s), earth:-2(m/s), up:0(m/s), yaw:0(deg/s) from current point for 2.2s!");
"--> Step 9: Move with north:-1.6(m/s), east:-2(m/s), up:0(m/s), yaw:0(deg/s) from current point for 2.2s!");
DjiTest_WidgetLogAppend(
"--> Step 9: Move with north:-1.6(m/s), earth:-2(m/s), up:0(m/s), yaw:0(deg/s) from current point for 2.2s!");
"--> Step 9: Move with north:-1.6(m/s), east:-2(m/s), up:0(m/s), yaw:0(deg/s) from current point for 2.2s!");
DjiTest_FlightControlVelocityAndYawRateCtrl((T_DjiTestFlightControlVector3f) {-1.6, -2, 0}, 0, 2200);
USER_LOG_INFO("--> Step 10: Emergency brake for 2s");
@ -669,6 +670,7 @@ void DjiTest_FlightControlSetGetParamSample()
E_DjiFlightControllerRtkPositionEnableStatus rtkEnableStatus;
E_DjiFlightControllerRCLostAction rcLostAction;
T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo;
uint16_t countryCode;
returnCode = DjiAircraftInfo_GetBaseInfo(&aircraftInfoBaseInfo);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
@ -678,6 +680,12 @@ void DjiTest_FlightControlSetGetParamSample()
USER_LOG_INFO("Flight control set-get-param sample start");
DjiTest_WidgetLogAppend("Flight control set-get-param sample start");
returnCode = DjiFlightController_GetCountryCode(&countryCode);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Get aircraft country code error.");
}
USER_LOG_INFO("country code: %hd", countryCode);
/*! Turn on horizontal vision avoid enable */
USER_LOG_INFO("--> Step 1: Turn on horizontal visual obstacle avoidance");
DjiTest_WidgetLogAppend("--> Step 1: Turn on horizontal visual obstacle avoidance");
@ -881,6 +889,97 @@ out:
DjiTest_WidgetLogAppend("Flight control set-get-param sample end");
}
T_DjiReturnCode DjiTest_TriggerFtsEventCallback(void)
{
USER_LOG_INFO("Received FTS Trigger event, count = %d.", s_ftsTriggerCount);
if (s_ftsTriggerCount == 0) {
USER_LOG_WARN("Note: Simulate a trigger failure scenario and return an error value, this function will be invoked again.");
s_ftsTriggerCount++;
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
} else {
USER_LOG_WARN("Note: This is an empty implementation, and the FTS signal needs to be triggered by the PWM signal.");
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
}
void DjiTest_FlightControlPassiveTriggerFtsSample(void)
{
T_DjiReturnCode returnCode;
USER_LOG_INFO("Flight control passive trigger FTS sample start.");
if (s_isFtsCallbackRegistered == false) {
returnCode = DjiFlightController_RegTriggerFtsEventCallback(DjiTest_TriggerFtsEventCallback);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Register trigger FTS event callback failed.");
return;
} else {
s_isFtsCallbackRegistered = true;
USER_LOG_INFO("Register trigger FTS event callback successfully."
"Please wait for the aircraft to trigger the payload to execute FTS action.");
}
} else {
USER_LOG_WARN("FTS trigger event callback has been registered, no need to register again.");
}
}
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) {
@ -908,6 +1007,14 @@ void DjiTest_FlightControlSample(E_DjiTestFlightCtrlSampleSelect flightCtrlSampl
DjiTest_FlightControlSetGetParamSample();
break;
}
case E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_FTS_TRIGGER: {
DjiTest_FlightControlPassiveTriggerFtsSample();
break;
}
case E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SLOW_ROTATE_BLADE: {
DjiTest_FlightControlSlowRotateMotorSample();
break;
}
default:
break;
}
@ -1218,6 +1325,12 @@ bool DjiTest_FlightControlGoHomeAndConfirmLanding(void)
{
T_DjiReturnCode djiStat;
T_DjiAircraftInfoBaseInfo aircraftInfoBaseInfo;
E_DjiFlightControllerObstacleAvoidanceEnableStatus enableStatus;
djiStat = DjiFlightController_GetDownwardsVisualObstacleAvoidanceEnableStatus(&enableStatus);
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("get downwards visual obstacle avoidance enable status error");
}
djiStat = DjiAircraftInfo_GetBaseInfo(&aircraftInfoBaseInfo);
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
@ -1251,8 +1364,16 @@ bool DjiTest_FlightControlGoHomeAndConfirmLanding(void)
DjiTest_FlightControlGetValueOfFlightStatus() == DJI_FC_SUBSCRIPTION_FLIGHT_STATUS_IN_AIR) {
T_DjiFcSubscriptionHeightFusion heightFusion = DjiTest_FlightControlGetValueOfHeightFusion();
s_osalHandler->TaskSleepMs(1000);
if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3E ||
aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3T) {
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_M3TA == 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
) {
if ((dji_f64_t) 0.45 < heightFusion && heightFusion < (dji_f64_t) 0.55) {
break;
}
@ -1272,11 +1393,20 @@ bool DjiTest_FlightControlGoHomeAndConfirmLanding(void)
return false;
}
if (!DjiTest_FlightControlCheckActionStarted(DJI_FC_SUBSCRIPTION_DISPLAY_MODE_FORCE_AUTO_LANDING)) {
return false;
if (enableStatus == DJI_FLIGHT_CONTROLLER_ENABLE_OBSTACLE_AVOIDANCE) {
if (!DjiTest_FlightControlCheckActionStarted(DJI_FC_SUBSCRIPTION_DISPLAY_MODE_FORCE_AUTO_LANDING)) {
return false;
} else {
while (DjiTest_FlightControlGetValueOfFlightStatus() == DJI_FC_SUBSCRIPTION_FLIGHT_STATUS_IN_AIR &&
DjiTest_FlightControlGetValueOfDisplayMode() ==
DJI_FC_SUBSCRIPTION_DISPLAY_MODE_FORCE_AUTO_LANDING) {
s_osalHandler->TaskSleepMs(1000);
}
}
} else {
while (DjiTest_FlightControlGetValueOfFlightStatus() == DJI_FC_SUBSCRIPTION_FLIGHT_STATUS_IN_AIR &&
DjiTest_FlightControlGetValueOfDisplayMode() == DJI_FC_SUBSCRIPTION_DISPLAY_MODE_FORCE_AUTO_LANDING) {
DjiTest_FlightControlGetValueOfDisplayMode() ==
DJI_FC_SUBSCRIPTION_DISPLAY_MODE_FORCE_AUTO_LANDING) {
s_osalHandler->TaskSleepMs(1000);
}
}
@ -1454,11 +1584,12 @@ DjiTest_FlightControlMoveByPositionOffset(const T_DjiTestFlightControlVector3f o
void DjiTest_FlightControlVelocityAndYawRateCtrl(const T_DjiTestFlightControlVector3f offsetDesired, float yawRate,
uint32_t timeMs)
{
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
uint32_t originTime = 0;
uint32_t currentTime = 0;
uint32_t elapsedTimeInMs = 0;
s_osalHandler->GetTimeMs(&originTime);
s_osalHandler->GetTimeMs(&currentTime);
osalHandler->GetTimeMs(&originTime);
osalHandler->GetTimeMs(&currentTime);
elapsedTimeInMs = currentTime - originTime;
T_DjiFlightControllerJoystickMode joystickMode = {
DJI_FLIGHT_CONTROLLER_HORIZONTAL_VELOCITY_CONTROL_MODE,
@ -1474,8 +1605,8 @@ void DjiTest_FlightControlVelocityAndYawRateCtrl(const T_DjiTestFlightControlVec
while (elapsedTimeInMs <= timeMs) {
DjiFlightController_ExecuteJoystickAction(joystickCommand);
s_osalHandler->TaskSleepMs(2);
s_osalHandler->GetTimeMs(&currentTime);
osalHandler->TaskSleepMs(2);
osalHandler->GetTimeMs(&currentTime);
elapsedTimeInMs = currentTime - originTime;
}
}
@ -1542,4 +1673,57 @@ DjiTest_FlightControlJoystickCtrlAuthSwitchEventCallback(T_DjiFlightControllerJo
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
static T_DjiReturnCode DjiTest_FlightControlSetFtsTrigger(E_DjiMountPosition position, const 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(E_DjiMountPosition position, const char* port_name)
{
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(position, port_name);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Test select %s fts pwm trigger failed", port_name);
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****/

View File

@ -42,12 +42,25 @@ typedef enum {
E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_TAKE_OFF_VELOCITY_CTRL_LANDING,
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)
typedef struct {
dji_f32_t x;
dji_f32_t y;
dji_f32_t z;
} T_DjiTestFlightControlVector3f; // pack(1)
#pragma pack()
/* Exported types ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
T_DjiReturnCode DjiTest_FlightControlRunSample(E_DjiTestFlightCtrlSampleSelect flightCtrlSampleSelect);
void DjiTest_FlightControlVelocityAndYawRateCtrl(const T_DjiTestFlightControlVector3f offsetDesired, float yawRate,
uint32_t timeMs);
T_DjiReturnCode DjiTest_FlightControlFtsPwmTriggerSample(E_DjiMountPosition position, const char* port_name);
#ifdef __cplusplus
}

View File

@ -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);

View File

@ -29,6 +29,8 @@
#include "dji_platform.h"
#include "dji_logger.h"
#include "dji_gimbal_manager.h"
#include "dji_fc_subscription.h"
#include "dji_aircraft_info.h"
/* Private constants ---------------------------------------------------------*/
@ -73,10 +75,34 @@ T_DjiReturnCode DjiTest_GimbalManagerRunSample(E_DjiMountPosition mountPosition,
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
T_DjiReturnCode returnCode;
T_DjiGimbalManagerRotation rotation;
T_DjiAircraftInfoBaseInfo baseInfo;
E_DjiAircraftSeries aircraftSeries;
bool gimbalAnglesSubscribedFlag = false;
returnCode = DjiAircraftInfo_GetBaseInfo(&baseInfo);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Failed to get aircraft base info, return code 0x%08X", returnCode);
goto out;
}
aircraftSeries = baseInfo.aircraftSeries;
USER_LOG_INFO("Gimbal manager sample start");
DjiTest_WidgetLogAppend("Gimbal manager sample start");
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");
DjiTest_WidgetLogAppend("--> Step 1: Init gimbal manager module");
returnCode = DjiGimbalManager_Init();
@ -99,7 +125,7 @@ T_DjiReturnCode DjiTest_GimbalManagerRunSample(E_DjiMountPosition mountPosition,
}
USER_LOG_INFO("--> Step 3: Reset gimbal angles.\r\n");
returnCode = DjiGimbalManager_Reset(mountPosition);
returnCode = DjiGimbalManager_Reset(mountPosition, DJI_GIMBAL_RESET_MODE_PITCH_AND_YAW);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Reset gimbal failed, error code: 0x%08X", returnCode);
}
@ -108,7 +134,7 @@ T_DjiReturnCode DjiTest_GimbalManagerRunSample(E_DjiMountPosition mountPosition,
for (int i = 0; i < sizeof(s_rotationActionList) / sizeof(T_DjiTestGimbalActionList); ++i) {
if (s_rotationActionList[i].action == DJI_TEST_GIMBAL_RESET) {
USER_LOG_INFO("Target gimbal reset.\r\n");
returnCode = DjiGimbalManager_Reset(mountPosition);
returnCode = DjiGimbalManager_Reset(mountPosition, DJI_GIMBAL_RESET_MODE_PITCH_AND_YAW);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Reset gimbal failed, error code: 0x%08X", returnCode);
}
@ -120,11 +146,27 @@ T_DjiReturnCode DjiTest_GimbalManagerRunSample(E_DjiMountPosition mountPosition,
continue;
}
USER_LOG_INFO("Target gimbal pry = (%.1f, %.1f, %.1f)",
s_rotationActionList[i].rotation.pitch, s_rotationActionList[i].rotation.roll,
s_rotationActionList[i].rotation.yaw);
rotation = s_rotationActionList[i].rotation;
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
) {
if (s_rotationActionList[i].rotation.rotationMode == DJI_GIMBAL_ROTATION_MODE_ABSOLUTE_ANGLE) {
T_DjiFcSubscriptionGimbalAngles gimbalAngles = {0};
T_DjiDataTimestamp timestamp = {0};
returnCode = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES,
(uint8_t *) &gimbalAngles,
sizeof(T_DjiFcSubscriptionGimbalAngles),
&timestamp);
rotation.yaw = gimbalAngles.z;
}
}
USER_LOG_INFO("Target gimbal pry = (%.1f, %.1f, %.1f)", rotation.pitch, rotation.roll, rotation.yaw);
returnCode = DjiGimbalManager_Rotate(mountPosition, rotation);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Target gimbal pry = (%.1f, %.1f, %.1f) failed, error code: 0x%08X",
@ -136,6 +178,14 @@ T_DjiReturnCode DjiTest_GimbalManagerRunSample(E_DjiMountPosition mountPosition,
}
}
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");
DjiTest_WidgetLogAppend("--> Step 5: Deinit gimbal manager module");
returnCode = DjiGimbalManager_Deinit();

File diff suppressed because it is too large Load Diff

View File

@ -25,6 +25,8 @@
/* Includes ------------------------------------------------------------------*/
#include <widget_interaction_test/test_widget_interaction.h>
#include <utils/util_misc.h>
#include <utils/cJSON.h>
#include <utils/util_file.h>
#include "test_hms.h"
#include "dji_hms.h"
#include "dji_hms_info_table.h"
@ -41,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 -------------------------------------------------------------*/
@ -49,31 +55,42 @@
static const char *oldReplaceAlarmIdStr = "%alarmid";
static const char *oldReplaceIndexStr = "%index";
static const char *oldReplaceComponentIndexStr = "%component_index";
static bool isHmsManagerInit = false;
static T_DjiHmsFileBinaryArray s_EnHmsTextConfigFileBinaryArrayList[] = {
{hms_text_config_json_fileName, hms_text_config_json_fileSize, hms_text_config_json_fileBinaryArray},
};
static bool s_hmsServiceRunFlag = false;
#ifdef SYSTEM_ARCH_LINUX
static uint8_t *s_hmsJsonData = NULL;
#endif
static E_DjiMobileAppLanguage s_hmsLanguage = DJI_MOBILE_APP_LANGUAGE_ENGLISH;
static bool s_isHmsConfigFileDirPathConfigured = false;
static char s_hmsConfigFileDirPath[DJI_FILE_PATH_SIZE_MAX] = {0};
/* Private functions declaration ---------------------------------------------*/
static T_DjiReturnCode DjiTest_HmsInit(void);
static T_DjiReturnCode DjiTest_HmsDeInit(void);
static T_DjiReturnCode DjiTest_HmsManagerInit(void);
static T_DjiReturnCode DjiTest_HmsManagerDeInit(void);
static T_DjiFcSubscriptionFlightStatus DjiTest_GetValueOfFlightStatus(void);
static bool DjiTest_ReplaceStr(char *buffer, uint32_t bufferMaxLen, const char *target, const char *dest);
static bool DjiTest_MarchErrCodeInfoTable(T_DjiHmsInfoTable hmsInfoTable);
#ifdef SYSTEM_ARCH_LINUX
static bool DjiTest_MarchErrCodeInfoTableByJson(T_DjiHmsInfoTable hmsInfoTable);
#endif
static T_DjiReturnCode DjiTest_HmsInfoCallback(T_DjiHmsInfoTable hmsInfoTable);
/* Exported functions definition ---------------------------------------------*/
T_DjiReturnCode DjiTest_HmsRunSample(void)
T_DjiReturnCode DjiTest_HmsManagerRunSample(E_DjiMobileAppLanguage language)
{
T_DjiReturnCode returnCode;
T_DjiOsalHandler *osalHandler;
s_hmsLanguage = language;
USER_LOG_INFO("Hms Sample Start");
DjiTest_WidgetLogAppend("Hms Sample Start");
USER_LOG_INFO("--> Step 1: Init hms sample");
DjiTest_WidgetLogAppend("--> Step 1: Init hms sample");
returnCode = DjiTest_HmsInit();
returnCode = DjiTest_HmsManagerInit();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Hms sample init error, error code:0x%08llX", returnCode);
goto out;
@ -82,7 +99,7 @@ T_DjiReturnCode DjiTest_HmsRunSample(void)
osalHandler = DjiPlatform_GetOsalHandler();
USER_LOG_INFO("--> Step 2: Register callback function of push HMS information");
DjiTest_WidgetLogAppend("--> Step 2: Register callback function of push HMS information");
returnCode = DjiHms_RegHmsInfoCallback(DjiTest_HmsInfoCallback);
returnCode = DjiHmsManager_RegHmsInfoCallback(DjiTest_HmsInfoCallback);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Register callback function of push HMS information failed, error code:0x%08llX", returnCode);
goto out;
@ -93,7 +110,7 @@ T_DjiReturnCode DjiTest_HmsRunSample(void)
out:
USER_LOG_INFO("--> Step 3: Deinit hms sample");
DjiTest_WidgetLogAppend("--> Step 3: Deinit hms sample");
returnCode = DjiTest_HmsDeInit();
returnCode = DjiTest_HmsManagerDeInit();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Hms sample deinit error, error code:0x%08llX", returnCode);
}
@ -104,7 +121,7 @@ out:
return returnCode;
}
T_DjiReturnCode DjiTest_HmsStartService(void)
T_DjiReturnCode DjiTest_HmsCustomizationStartService(void)
{
T_DjiReturnCode returnCode;
#ifdef SYSTEM_ARCH_LINUX
@ -112,7 +129,7 @@ T_DjiReturnCode DjiTest_HmsStartService(void)
char tempPath[HMS_DIR_PATH_LEN_MAX];
#endif
returnCode = DjiHms_Init();
returnCode = DjiHmsCustomization_Init();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Hms init error, error code:0x%08llX", returnCode);
return returnCode;
@ -126,27 +143,36 @@ T_DjiReturnCode DjiTest_HmsStartService(void)
return returnCode;
}
snprintf(tempPath, HMS_DIR_PATH_LEN_MAX, "%shms_text/en", curFileDirPath);
if (s_isHmsConfigFileDirPathConfigured == true) {
snprintf(tempPath, HMS_DIR_PATH_LEN_MAX, "%shms_text/en", s_hmsConfigFileDirPath);
} else {
snprintf(tempPath, HMS_DIR_PATH_LEN_MAX, "%shms_text/en", curFileDirPath);
}
//set default hms text config path
returnCode = DjiHms_RegDefaultHmsTextConfigByDirPath(tempPath);
returnCode = DjiHmsCustomization_RegDefaultHmsTextConfigByDirPath(tempPath);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Add default hms text config error, stat = 0x%08llX", returnCode);
return returnCode;
}
//set hms text config for English language
returnCode = DjiHms_RegHmsTextConfigByDirPath(DJI_MOBILE_APP_LANGUAGE_ENGLISH,
tempPath);
returnCode = DjiHmsCustomization_RegHmsTextConfigByDirPath(DJI_MOBILE_APP_LANGUAGE_ENGLISH,
tempPath);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Add hms text config error, stat = 0x%08llX", returnCode);
return returnCode;
}
//set hms text config for Chinese language
snprintf(tempPath, HMS_DIR_PATH_LEN_MAX, "%shms_text/cn", curFileDirPath);
returnCode = DjiHms_RegHmsTextConfigByDirPath(DJI_MOBILE_APP_LANGUAGE_CHINESE,
tempPath);
if (s_isHmsConfigFileDirPathConfigured == true) {
snprintf(tempPath, HMS_DIR_PATH_LEN_MAX, "%shms_text/cn", s_hmsConfigFileDirPath);
} else {
snprintf(tempPath, HMS_DIR_PATH_LEN_MAX, "%shms_text/cn", curFileDirPath);
}
returnCode = DjiHmsCustomization_RegHmsTextConfigByDirPath(DJI_MOBILE_APP_LANGUAGE_CHINESE,
tempPath);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Add hms text config error, stat = 0x%08llX", returnCode);
return returnCode;
@ -159,7 +185,7 @@ T_DjiReturnCode DjiTest_HmsStartService(void)
};
//set default hms text config
returnCode = DjiHms_RegDefaultHmsTextConfigByBinaryArray(&enHmsTextBinaryArrayConfig);
returnCode = DjiHmsCustomization_RegDefaultHmsTextConfigByBinaryArray(&enHmsTextBinaryArrayConfig);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Add default hms text config error, stat = 0x%08llX", returnCode);
return returnCode;
@ -167,18 +193,34 @@ T_DjiReturnCode DjiTest_HmsStartService(void)
#endif
#if DJI_CUSTOM_HMS_CODE_INJECT_ON
DjiHms_InjectHmsErrorCode(0x1E020000, DJI_HMS_ERROR_LEVEL_FATAL);
DjiHmsCustomization_InjectHmsErrorCode(0x1E020000, DJI_HMS_ERROR_LEVEL_FATAL);
DjiHmsCustomization_InjectHmsErrorCode(0x1E020001, DJI_HMS_ERROR_LEVEL_CRITICAL);
DjiHmsCustomization_InjectHmsErrorCode(0x1E020002, DJI_HMS_ERROR_LEVEL_WARN);
DjiHmsCustomization_InjectHmsErrorCode(0x1E020003, DJI_HMS_ERROR_LEVEL_HINT);
#endif
s_hmsServiceRunFlag = true;
return returnCode;
}
T_DjiReturnCode DjiTest_HmsCustomizationSetConfigFilePath(const char *path)
{
memset(s_hmsConfigFileDirPath, 0, sizeof(s_hmsConfigFileDirPath));
memcpy(s_hmsConfigFileDirPath, path, USER_UTIL_MIN(strlen(path), sizeof(s_hmsConfigFileDirPath) - 1));
s_isHmsConfigFileDirPathConfigured = true;
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
/* Private functions definition-----------------------------------------------*/
static T_DjiReturnCode DjiTest_HmsInit(void)
static T_DjiReturnCode DjiTest_HmsManagerInit(void)
{
T_DjiReturnCode returnCode;
#ifdef SYSTEM_ARCH_LINUX
char curFileDirPath[HMS_DIR_PATH_LEN_MAX];
char tempFileDirPath[HMS_DIR_PATH_LEN_MAX];
uint32_t fileSize = 0;
uint32_t readRealSize = 0;
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
#endif
returnCode = DjiFcSubscription_Init();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
@ -190,22 +232,48 @@ static T_DjiReturnCode DjiTest_HmsInit(void)
returnCode = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_STATUS_FLIGHT,
DJI_DATA_SUBSCRIPTION_TOPIC_10_HZ,
NULL);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("HMS sample subscribe topic flight status error, error code:0x%08llX", returnCode);
return returnCode;
}
if (s_hmsServiceRunFlag == true) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
#ifdef SYSTEM_ARCH_LINUX
returnCode = DjiUserUtil_GetCurrentFileDirPath(__FILE__, HMS_DIR_PATH_LEN_MAX, curFileDirPath);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Get file current path error, stat = 0x%08llX", returnCode);
return returnCode;
}
return DjiHms_Init();
snprintf(tempFileDirPath, HMS_DIR_PATH_LEN_MAX, "%s/data/hms.json", curFileDirPath);
returnCode = UtilFile_GetFileSizeByPath(tempFileDirPath, &fileSize);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Get file size by path failed, stat = 0x%08llX", returnCode);
return returnCode;
}
USER_LOG_DEBUG("Hms json file size is %d", fileSize);
s_hmsJsonData = osalHandler->Malloc(fileSize);
if (s_hmsJsonData == NULL) {
USER_LOG_ERROR("Malloc failed.");
}
UtilFile_GetFileDataByPath(tempFileDirPath, 0, fileSize, s_hmsJsonData, &readRealSize);
#endif
isHmsManagerInit = true;
return DjiHmsManager_Init();
}
static T_DjiReturnCode DjiTest_HmsDeInit(void)
static T_DjiReturnCode DjiTest_HmsManagerDeInit(void)
{
T_DjiReturnCode returnCode;
#ifdef SYSTEM_ARCH_LINUX
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
#endif
returnCode = DjiFcSubscription_DeInit();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
@ -214,11 +282,13 @@ static T_DjiReturnCode DjiTest_HmsDeInit(void)
return returnCode;
}
if (s_hmsServiceRunFlag == true) {
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
#ifdef SYSTEM_ARCH_LINUX
osalHandler->Free(s_hmsJsonData);
#endif
return DjiHms_DeInit();
isHmsManagerInit = false;
return DjiHmsManager_DeInit();
}
static T_DjiFcSubscriptionFlightStatus DjiTest_GetValueOfFlightStatus(void)
@ -227,6 +297,10 @@ static T_DjiFcSubscriptionFlightStatus DjiTest_GetValueOfFlightStatus(void)
T_DjiFcSubscriptionFlightStatus flightStatus;
T_DjiDataTimestamp flightStatusTimestamp = {0};
if (isHmsManagerInit == false) {
return DJI_FC_SUBSCRIPTION_FLIGHT_STATUS_ON_GROUND;
}
returnCode = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_STATUS_FLIGHT,
(uint8_t *) &flightStatus,
sizeof(T_DjiFcSubscriptionFlightStatus),
@ -326,12 +400,71 @@ static bool DjiTest_MarchErrCodeInfoTable(T_DjiHmsInfoTable hmsInfoTable)
return true;
}
#ifdef SYSTEM_ARCH_LINUX
static bool DjiTest_MarchErrCodeInfoTableByJson(T_DjiHmsInfoTable hmsInfoTable)
{
cJSON *hmsJsonRoot = NULL;
cJSON *hmsErrorCode = NULL;
cJSON *hmsLanguage = NULL;
char hmsErrorCodeString[HMS_DIR_PATH_LEN_MAX] = {0};
hmsJsonRoot = cJSON_Parse((char *) s_hmsJsonData);
if (hmsJsonRoot == NULL) {
return 0;
}
for (int i = 0; i < hmsInfoTable.hmsInfoNum; i++) {
if (DjiTest_GetValueOfFlightStatus() == DJI_FC_SUBSCRIPTION_FLIGHT_STATUS_IN_AIR) {
sprintf(hmsErrorCodeString, "fpv_tip_0x%08X_in_the_sky", hmsInfoTable.hmsInfo[i].errorCode);
} else {
sprintf(hmsErrorCodeString, "fpv_tip_0x%08X", hmsInfoTable.hmsInfo[i].errorCode);
}
hmsErrorCode = cJSON_GetObjectItem(hmsJsonRoot, hmsErrorCodeString);
if (hmsErrorCode != NULL) {
if (s_hmsLanguage == DJI_MOBILE_APP_LANGUAGE_CHINESE) {
hmsLanguage = cJSON_GetObjectItem(hmsErrorCode, "zh");
} else if (s_hmsLanguage == DJI_MOBILE_APP_LANGUAGE_ENGLISH) {
hmsLanguage = cJSON_GetObjectItem(hmsErrorCode, "en");
} else if (s_hmsLanguage == DJI_MOBILE_APP_LANGUAGE_JAPANESE) {
hmsLanguage = cJSON_GetObjectItem(hmsErrorCode, "ja");
} else if (s_hmsLanguage == DJI_MOBILE_APP_LANGUAGE_FRENCH) {
hmsLanguage = cJSON_GetObjectItem(hmsErrorCode, "fr");
}
if (hmsLanguage != NULL) {
if (hmsInfoTable.hmsInfo[i].errorLevel > MIN_HMS_ERROR_LEVEL &&
hmsInfoTable.hmsInfo[i].errorLevel < MID_HMS_ERROR_LEVEL) {
USER_LOG_WARN("[ErrorCode: 0x%2x]: %s", hmsInfoTable.hmsInfo[i].errorCode,
hmsLanguage->valuestring);
} else if (hmsInfoTable.hmsInfo[i].errorLevel >= MID_HMS_ERROR_LEVEL &&
hmsInfoTable.hmsInfo[i].errorLevel < MAX_HMS_ERROR_LEVEL) {
USER_LOG_ERROR("[ErrorCode: 0x%2x]: %s", hmsInfoTable.hmsInfo[i].errorCode,
hmsLanguage->valuestring);
}
} else {
USER_LOG_WARN("[ErrorCode: 0x%2x] There are no matching documents for this language for now.",
hmsInfoTable.hmsInfo[i].errorCode);
}
} else {
USER_LOG_WARN("[ErrorCode: 0x%2x] There are no matching documents in the current json for now.",
hmsInfoTable.hmsInfo[i].errorCode);
}
}
cJSON_Delete(hmsJsonRoot);
}
#endif
static T_DjiReturnCode DjiTest_HmsInfoCallback(T_DjiHmsInfoTable hmsInfoTable)
{
#ifdef SYSTEM_ARCH_LINUX
DjiTest_MarchErrCodeInfoTableByJson(hmsInfoTable);
#else
if (!DjiTest_MarchErrCodeInfoTable(hmsInfoTable)) {
USER_LOG_ERROR("March HMS Information failed.");
return DJI_ERROR_SYSTEM_MODULE_CODE_UNKNOWN;
}
#endif
if (hmsInfoTable.hmsInfoNum == 0) {
USER_LOG_INFO("All systems of drone are running well now.");

View File

@ -39,8 +39,9 @@ extern "C" {
/* Exported types ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
T_DjiReturnCode DjiTest_HmsRunSample(void);
T_DjiReturnCode DjiTest_HmsStartService(void);
T_DjiReturnCode DjiTest_HmsManagerRunSample(E_DjiMobileAppLanguage language);
T_DjiReturnCode DjiTest_HmsCustomizationStartService(void);
T_DjiReturnCode DjiTest_HmsCustomizationSetConfigFilePath(const char *path);
#ifdef __cplusplus
}

View File

@ -0,0 +1,155 @@
/**
********************************************************************
* @file test_interest_point.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 DJIs 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_interest_point.h"
#include "dji_interest_point.h"
#include "dji_logger.h"
#include "dji_flight_controller.h"
#include "flight_control/test_flight_control.h"
#include "dji_aircraft_info.h"
/* Private constants ---------------------------------------------------------*/
/* Private types -------------------------------------------------------------*/
/* Private values -------------------------------------------------------------*/
static T_DjiReturnCode DjiUser_InterestPointMissionStateCallback(T_DjiInterestPointMissionState missionState);
/* Private functions declaration ---------------------------------------------*/
/* Exported functions definition ---------------------------------------------*/
T_DjiReturnCode DjiTest_InterestPointRunSample(void)
{
T_DjiReturnCode returnCode;
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);
return returnCode;
}
returnCode = DjiInterestPoint_Init();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Point interest init failed, errno=%lld", returnCode);
return returnCode;
}
osalHandler->TaskSleepMs(1000);
DjiFlightController_ObtainJoystickCtrlAuthority();
osalHandler->TaskSleepMs(1000);
DjiFlightController_StartTakeoff();
osalHandler->TaskSleepMs(1000);
DjiTest_FlightControlVelocityAndYawRateCtrl((T_DjiTestFlightControlVector3f) {0, 0, 5}, 0, 10000);
osalHandler->TaskSleepMs(1000);
DjiTest_FlightControlVelocityAndYawRateCtrl((T_DjiTestFlightControlVector3f) {3, 0, 0}, 0, 5000);
interestPointSettings.latitude = 22.57775;
interestPointSettings.longitude = 113.94265;
returnCode = DjiInterestPoint_RegMissionStateCallback(DjiUser_InterestPointMissionStateCallback);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Register mission state callback failed, errno=%lld", returnCode);
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;
}
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();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Point interest deinit failed, errno=%lld", returnCode);
return returnCode;
}
returnCode = DjiFlightController_DeInit();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Flight control init failed, errno=%lld", returnCode);
return returnCode;
}
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
}
/* Private functions definition-----------------------------------------------*/
static T_DjiReturnCode DjiUser_InterestPointMissionStateCallback(T_DjiInterestPointMissionState missionState)
{
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;
}
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/

View File

@ -0,0 +1,49 @@
/**
********************************************************************
* @file test_interest_point.h
* @brief This is the header file for "test_interest_point.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 DJIs 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_INTEREST_POINT_H
#define TEST_INTEREST_POINT_H
/* Includes ------------------------------------------------------------------*/
#include "dji_typedef.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported functions --------------------------------------------------------*/
T_DjiReturnCode DjiTest_InterestPointRunSample(void);
#ifdef __cplusplus
}
#endif
#endif // TEST_INTEREST_POINT_H
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/

View File

@ -77,14 +77,14 @@ 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.aircraftType == DJI_AIRCRAFT_TYPE_M3E) {
//TODO: how to use on M3E
} else if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3T) {
//TODO: how to use on M3T
} else {
if (aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M300 ||
aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M350 ||
aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M30 ||
aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M400) {
localTime = localtime(&currentTime);
sprintf(s_fpvCameraStreamFilePath, "fpv_stream_%04d%02d%02d_%02d-%02d-%02d.h264",
localTime->tm_year + 1900, localTime->tm_mon + 1, localTime->tm_mday,
@ -98,8 +98,23 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition)
}
}
if (aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M400
&& aircraftInfoBaseInfo.mountPositionType == DJI_MOUNT_POSITION_TYPE_MANIFOLD3_ONBOARD)
{
// XXX: On MANIFOLD3, FPV and MAIN CAMERA SOURCE_DEFAULT streams cannot be subscribed to at the same time.
for (int i = 0; i < TEST_LIVEVIEW_STREAM_STROING_TIME_IN_SECONDS; ++i) {
USER_LOG_INFO("Storing camera h264 stream, second: %d.", i + 1);
osalHandler->TaskSleepMs(1000);
}
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);
goto out;
}
}
localTime = localtime(&currentTime);
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);
@ -113,12 +128,17 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition)
for (int i = 0; i < TEST_LIVEVIEW_STREAM_STROING_TIME_IN_SECONDS; ++i) {
USER_LOG_INFO("Storing camera h264 stream, second: %d.", i + 1);
#if TEST_LIVEVIEW_STREAM_REQUEST_I_FRAME_ON
if (i % TEST_LIVEVIEW_STREAM_REQUEST_I_FRAME_TICK_IN_SECONDS == 0) {
returnCode = DjiLiveview_RequestIntraframeFrameData((E_DjiLiveViewCameraPosition) mountPosition,
DJI_LIVEVIEW_CAMERA_SOURCE_DEFAULT);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Request stream I frame of payload %d failed, error code: 0x%08X", mountPosition,
returnCode);
if (aircraftInfoBaseInfo.mountPositionType != DJI_MOUNT_POSITION_TYPE_MANIFOLD3_ONBOARD)
{
if (i % TEST_LIVEVIEW_STREAM_REQUEST_I_FRAME_TICK_IN_SECONDS == 0)
{
returnCode = DjiLiveview_RequestIntraframeFrameData((E_DjiLiveViewCameraPosition)mountPosition,
DJI_LIVEVIEW_CAMERA_SOURCE_DEFAULT);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS)
{
USER_LOG_ERROR("Request stream I frame of payload %d failed, error code: 0x%08X", mountPosition,
returnCode);
}
}
}
#endif
@ -127,11 +147,11 @@ T_DjiReturnCode DjiTest_LiveviewRunSample(E_DjiMountPosition mountPosition)
USER_LOG_INFO("--> Step 3: Stop h264 stream of the fpv and selected payload\r\n");
DjiTest_WidgetLogAppend("--> Step 3: Stop h264 stream of the fpv and selected payload");
if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3E) {
} else if (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3T) {
} else {
if (aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M300 ||
aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M350 ||
aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M30 ||
(aircraftInfoBaseInfo.aircraftSeries == DJI_AIRCRAFT_SERIES_M400
&& aircraftInfoBaseInfo.mountPositionType != DJI_MOUNT_POSITION_TYPE_MANIFOLD3_ONBOARD)) {
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);
@ -146,10 +166,12 @@ 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 (aircraftInfoBaseInfo.aircraftType == DJI_AIRCRAFT_TYPE_M3T) {
if (DJI_AIRCRAFT_TYPE_M3T == aircraftInfoBaseInfo.aircraftType
|| DJI_AIRCRAFT_TYPE_M3TA == aircraftInfoBaseInfo.aircraftType
|| DJI_AIRCRAFT_TYPE_M3TD == aircraftInfoBaseInfo.aircraftType
|| DJI_AIRCRAFT_TYPE_M4T == aircraftInfoBaseInfo.aircraftType
|| DJI_AIRCRAFT_TYPE_M4TD == aircraftInfoBaseInfo.aircraftType
) {
USER_LOG_INFO("--> Start h264 stream of the fpv and selected payload\r\n");
localTime = localtime(&currentTime);

View File

@ -180,7 +180,7 @@ REWAIT:
}
sendDataCount++;
memset(sendBuf, sendDataCount, TEST_MOP_CHANNEL_NORMAL_TRANSFOR_SEND_BUFFER);
memset(sendBuf, 'A' - 1 + (sendDataCount % 26), TEST_MOP_CHANNEL_NORMAL_TRANSFOR_SEND_BUFFER);
returnCode = DjiMopChannel_SendData(s_testMopChannelNormalOutHandle, sendBuf,
TEST_MOP_CHANNEL_NORMAL_TRANSFOR_SEND_BUFFER, &realLen);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
@ -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) {

Some files were not shown because too many files have changed in this diff Show More