NEW: release DJI Payload-SDK version 3.6
Signed-off-by: DJI-Martin <DJI-Martin@dji.com>
This commit is contained in:
@ -54,6 +54,22 @@ 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 |",
|
||||
};
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
|
||||
@ -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"
|
||||
}
|
||||
}
|
||||
File diff suppressed because it is too large
Load Diff
@ -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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef TEST_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******/
|
||||
@ -0,0 +1,109 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <iostream>
|
||||
#include <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"
|
||||
<< 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 'q':
|
||||
break;
|
||||
default:
|
||||
USER_LOG_ERROR("Input command is invalid");
|
||||
goto start;
|
||||
}
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF 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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef TEST_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******/
|
||||
@ -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);
|
||||
@ -110,6 +131,297 @@ 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;
|
||||
|
||||
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) {
|
||||
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.");
|
||||
}
|
||||
|
||||
|
||||
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),
|
||||
×tamp);
|
||||
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),
|
||||
×tamp);
|
||||
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),
|
||||
×tamp);
|
||||
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) {
|
||||
returnCode = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES,
|
||||
(uint8_t *) &gimbalAngles,
|
||||
sizeof(T_DjiFcSubscriptionGimbalAngles),
|
||||
×tamp);
|
||||
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 +429,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-----------------------------------------------*/
|
||||
|
||||
@ -0,0 +1,82 @@
|
||||
/**
|
||||
********************************************************************
|
||||
* @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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "hms_manager_entry.h"
|
||||
#include "dji_platform.h"
|
||||
#include <iostream>
|
||||
#include "dji_logger.h"
|
||||
#include "hms/test_hms.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;
|
||||
}
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
@ -0,0 +1,49 @@
|
||||
|
||||
/**
|
||||
********************************************************************
|
||||
* @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 DJI’s authorization, you may not
|
||||
* further disseminate the information, and you must immediately remove the
|
||||
* source code and notify DJI of its removal. DJI reserves the right to pursue
|
||||
* legal actions against you for any loss(es) or damage(s) caused by your
|
||||
* failure to do so.
|
||||
*
|
||||
*********************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef 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);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // HMS_MANAGER_ENTRY_H
|
||||
/************************ (C) COPYRIGHT DJI Innovations *******END OF FILE******/
|
||||
Reference in New Issue
Block a user