M350b版本
This commit is contained in:
@ -109,18 +109,10 @@ void DjiUser_RunCameraManagerSample(void)
|
||||
<< "| Available position: |"
|
||||
<<
|
||||
endl;
|
||||
cout
|
||||
<< "| [1] Select gimbal mount position at NO.1 payload port |"
|
||||
<<
|
||||
endl;
|
||||
cout
|
||||
<< "| [2] Select gimbal mount position at NO.2 payload port |"
|
||||
<<
|
||||
endl;
|
||||
cout
|
||||
<< "| [3] Select gimbal mount position at NO.3 payload port |"
|
||||
<<
|
||||
endl;
|
||||
std::cout
|
||||
<< "| [1 ~ 4] Select camera mount position at NO.1~NO.4 |"
|
||||
<<
|
||||
std::endl;
|
||||
cout
|
||||
<< "| [q] Quit |"
|
||||
<<
|
||||
@ -134,7 +126,7 @@ void DjiUser_RunCameraManagerSample(void)
|
||||
|
||||
posNum = atoi(mountPositionStr.c_str());
|
||||
|
||||
if (posNum > 3 || posNum < 1) {
|
||||
if (posNum > 4 || posNum < 1) {
|
||||
USER_LOG_ERROR("Input mount position is invalid");
|
||||
continue;
|
||||
} else {
|
||||
|
||||
@ -23,16 +23,25 @@
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
|
||||
#include <termios.h>
|
||||
|
||||
#include <utils/util_misc.h>
|
||||
|
||||
#include <utils/util_file.h>
|
||||
#include <utils/cJSON.h>
|
||||
#include <dji_aircraft_info.h>
|
||||
#include "test_flight_controller_command_flying.h"
|
||||
#include "dji_flight_controller.h"
|
||||
#include "dji_logger.h"
|
||||
#include "dji_fc_subscription.h"
|
||||
#include "cmath"
|
||||
#include <utils/cJSON.h>
|
||||
|
||||
#include <dji_aircraft_info.h>
|
||||
|
||||
#include "test_flight_controller_command_flying.h"
|
||||
|
||||
#include "dji_flight_controller.h"
|
||||
#include "cmath"
|
||||
#include "dji_logger.h"
|
||||
#include "cmath"
|
||||
#include "dji_fc_subscription.h"
|
||||
|
||||
|
||||
#ifdef OPEN_CV_INSTALLED
|
||||
|
||||
@ -84,6 +93,7 @@ static T_DjiFcSubscriptionControlDevice DjiUser_FlightControlGetValueOfControlDe
|
||||
static T_DjiFcSubscriptionSingleBatteryInfo DjiUser_FlightControlGetValueOfBattery1(void);
|
||||
static T_DjiFcSubscriptionSingleBatteryInfo DjiUser_FlightControlGetValueOfBattery2(void);
|
||||
static T_DjiReturnCode DjiUser_FlightControlUpdateConfig(void);
|
||||
static T_DjiReturnCode DjiUser_ShowCommandFlyingMenu(void);
|
||||
|
||||
/* Exported functions definition ---------------------------------------------*/
|
||||
void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
@ -107,7 +117,9 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
return;
|
||||
}
|
||||
|
||||
osalHandler->TaskSleepMs(1000);
|
||||
osalHandler->TaskSleepMs(3000);
|
||||
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
|
||||
while (1) {
|
||||
osalHandler->TaskSleepMs(1);
|
||||
@ -119,7 +131,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = 0;
|
||||
s_flyingCommand.yaw = 0;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Front\r\n");
|
||||
break;
|
||||
case 'S':
|
||||
case 's':
|
||||
@ -128,7 +139,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = 0;
|
||||
s_flyingCommand.yaw = 0;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Near\r\n");
|
||||
break;
|
||||
case 'A':
|
||||
case 'a':
|
||||
@ -137,7 +147,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = 0;
|
||||
s_flyingCommand.yaw = 0;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Left\r\n");
|
||||
break;
|
||||
case 'D':
|
||||
case 'd':
|
||||
@ -146,7 +155,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = 0;
|
||||
s_flyingCommand.yaw = 0;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Right\r\n");
|
||||
break;
|
||||
case 'Q':
|
||||
case 'q':
|
||||
@ -155,7 +163,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = s_flyingSpeed;
|
||||
s_flyingCommand.yaw = 0;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Up\r\n");
|
||||
break;
|
||||
case 'E':
|
||||
case 'e':
|
||||
@ -164,7 +171,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = -s_flyingSpeed;
|
||||
s_flyingCommand.yaw = 0;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Down\r\n");
|
||||
break;
|
||||
case 'Z':
|
||||
case 'z':
|
||||
@ -173,7 +179,6 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = 0;
|
||||
s_flyingCommand.yaw = -30;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Yaw--\r\n");
|
||||
break;
|
||||
case 'C':
|
||||
case 'c':
|
||||
@ -182,96 +187,112 @@ void DjiUser_RunFlightControllerCommandFlyingSample(void)
|
||||
s_flyingCommand.z = 0;
|
||||
s_flyingCommand.yaw = 30;
|
||||
s_inputFlag = 0;
|
||||
USER_LOG_INFO(" - Yaw++\r\n");
|
||||
break;
|
||||
case 'R':
|
||||
case 'r':
|
||||
DjiFlightController_ObtainJoystickCtrlAuthority();
|
||||
DjiFlightController_StartTakeoff();
|
||||
USER_LOG_INFO(" - Take off\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'F':
|
||||
case 'f':
|
||||
DjiFlightController_StartForceLanding();
|
||||
USER_LOG_INFO(" - Force landing\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'H':
|
||||
case 'h':
|
||||
DjiFlightController_StartGoHome();
|
||||
USER_LOG_INFO(" - Start go home\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'Y':
|
||||
case 'y':
|
||||
DjiFlightController_CancelGoHome();
|
||||
USER_LOG_INFO(" - Cancel go home\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'G':
|
||||
case 'g':
|
||||
DjiFlightController_StartLanding();
|
||||
USER_LOG_INFO(" - Start landing\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'T':
|
||||
case 't':
|
||||
DjiFlightController_CancelLanding();
|
||||
USER_LOG_INFO(" - Cancel landing\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'V':
|
||||
case 'v':
|
||||
DjiFlightController_StartConfirmLanding();
|
||||
USER_LOG_INFO(" - Confirm landing\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'X':
|
||||
case 'x':
|
||||
s_homeLocation.longitude = (dji_f64_t) s_gpsPosition.x / 10000000;
|
||||
s_homeLocation.latitude = (dji_f64_t) s_gpsPosition.y / 10000000;
|
||||
DjiFlightController_SetHomeLocationUsingCurrentAircraftLocation();
|
||||
USER_LOG_INFO(" - Set home location\r\n");
|
||||
USER_LOG_INFO(" - Set home location (%.4f, %.4f)\r\n", s_homeLocation.longitude, s_homeLocation.latitude);
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'P':
|
||||
case 'p':
|
||||
DjiFlightController_EmergencyStopMotor(DJI_FLIGHT_CONTROLLER_ENABLE_EMERGENCY_STOP_MOTOR,
|
||||
(char *) "Test is ok");
|
||||
USER_LOG_INFO(" - Emergency stop motor\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'B':
|
||||
case 'b':
|
||||
DjiFlightController_TurnOnMotors();
|
||||
USER_LOG_INFO(" - Turn on motors\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'N':
|
||||
case 'n':
|
||||
DjiFlightController_TurnOffMotors();
|
||||
USER_LOG_INFO(" - Turn off motors\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'J':
|
||||
case 'j':
|
||||
DjiUser_FlightControlUpdateConfig();
|
||||
USER_LOG_INFO(" - Update config\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'I':
|
||||
case 'i':
|
||||
DjiFlightController_ArrestFlying();
|
||||
USER_LOG_INFO(" - Enable arrest flying\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'O':
|
||||
case 'o':
|
||||
DjiFlightController_CancelArrestFlying();
|
||||
USER_LOG_INFO(" - Disable arrest flying\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'K':
|
||||
case 'k':
|
||||
DjiFlightController_ExecuteEmergencyBrakeAction();
|
||||
USER_LOG_INFO(" - Brake\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'L':
|
||||
case 'l':
|
||||
DjiFlightController_CancelEmergencyBrakeAction();
|
||||
USER_LOG_INFO(" - Disable Brake\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
case 'M':
|
||||
case 'm':
|
||||
DjiFlightController_ObtainJoystickCtrlAuthority();
|
||||
USER_LOG_INFO(" - Obtain joystick ctrl authority\r\n");
|
||||
DjiUser_ShowCommandFlyingMenu();
|
||||
break;
|
||||
}
|
||||
}
|
||||
@ -603,6 +624,9 @@ DjiUser_FlightCtrlJoystickCtrlAuthSwitchEventCb(T_DjiFlightControllerJoystickCtr
|
||||
case DJI_FLIGHT_CONTROLLER_NERA_FLIGHT_BOUNDARY_RESET_JOYSTICK_CTRL_AUTH_EVENT :
|
||||
USER_LOG_INFO("[Event] Current joystick ctrl authority is reset to rc due to near boundary\r\n");
|
||||
break;
|
||||
case DJI_FLIGHT_CONTROLLER_DOCK_REQUEST_CHANGE_JOYSTICK_CTRL_AUTH_EVENT :
|
||||
USER_LOG_INFO("[Event]Current joystick ctrl authority is change due to the dock request\r\n");
|
||||
break;
|
||||
default:
|
||||
USER_LOG_INFO("[Event] Unknown joystick ctrl authority event\r\n");
|
||||
}
|
||||
@ -1086,5 +1110,22 @@ static T_DjiReturnCode DjiUser_FlightControlUpdateConfig(void)
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
#endif
|
||||
}
|
||||
static T_DjiReturnCode DjiUser_ShowCommandFlyingMenu(void)
|
||||
{
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
|
||||
osalHandler->TaskSleepMs(2);
|
||||
USER_LOG_INFO("Usage: [W] Front [A]-Left, [S]-Rear, [D]-Right");
|
||||
USER_LOG_INFO("Usage: [Q]-Up [E]-Down, [Z]-Yaw--, [C]-Yaw++");
|
||||
USER_LOG_INFO("Usage: [R]-Take off [F]-Force landing, [H]-Start go home, [Y]-Cancel go home");
|
||||
USER_LOG_INFO("Usage: [G]-Start landing [T]-Cancel landing, [V]-Confirm landing, [X]-Set home location");
|
||||
USER_LOG_INFO("Usage: [P]-Emergency stop motor, [B]-Turn on motors, [N]-Turn off motors, [J]-Update config");
|
||||
USER_LOG_INFO("Usage: [I]-Enable arrest flying, [O]-Disable arrest flying, [K]-Emergency brake, [L]-Diasble Brake");
|
||||
USER_LOG_INFO("Usage: [M]-Obtain joystick ctrl authority");
|
||||
osalHandler->TaskSleepMs(2);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
|
||||
@ -63,6 +63,11 @@ start:
|
||||
<< "| [8] Waypoint 3.0 sample - run airline mission by kmz file (not support on M300 RTK) |\n"
|
||||
<< "| [9] Interest point sample - run interest point mission by settings (only support on M3E/M3T) |\n"
|
||||
<< "| [a] EU-C6 FTS trigger sample - receive fts callback to trigger parachute function (only support on M3D/M3DT) |\n"
|
||||
<< "| [b] Slow rotate blade sample, only support on M400 |\n"
|
||||
<< "| [c] Select FTS pwm trigger position, support on M4/M4T/M4D/M4TD |\n"
|
||||
<< "| [d] Select FTS pwm trigger position, support on M400 |\n"
|
||||
<< "| [e] Flight controller sample - set get perception parameters, support on M400 |\n"
|
||||
<< "| [f] Flight controller sample - set cmd start mission, support on M400 |\n"
|
||||
<< std::endl;
|
||||
|
||||
std::cin >> inputSelectSample;
|
||||
@ -100,6 +105,23 @@ start:
|
||||
case 'a':
|
||||
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_FTS_TRIGGER);
|
||||
break;
|
||||
case 'b':
|
||||
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SLOW_ROTATE_BLADE);
|
||||
break;
|
||||
case 'c':
|
||||
DjiTest_FtsPwmTriggerSample(DJI_MOUNT_POSITION_EXTENSION_PORT, "DJI_MOUNT_POSITION_EXTENSION_PORT");
|
||||
// or DJI_MOUNT_POSITION_EXTENSION_LITE_PORT
|
||||
DjiTest_FtsPwmTriggerSample(DJI_MOUNT_POSITION_EXTENSION_LITE_PORT, "DJI_MOUNT_POSITION_EXTENSION_LITE_PORT");
|
||||
break;
|
||||
case 'd': // for m400
|
||||
DjiTest_FtsPwmTriggerSample(DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO4, "DJI_MOUNT_POSITION_EXTENSION_PORT_V2_NO4");
|
||||
break;
|
||||
case 'e' : // for m400
|
||||
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SET_GET_PERCEPTION_PARAM);
|
||||
goto start;
|
||||
case 'f' : // for m400
|
||||
DjiTest_FlightControlRunSample(E_DJI_TEST_FLIGHT_CTRL_SAMPLE_SELECT_SET_CMD_START_MISSION);
|
||||
goto start;
|
||||
case 'q':
|
||||
break;
|
||||
default:
|
||||
|
||||
@ -89,15 +89,7 @@ start:
|
||||
<<
|
||||
std::endl;
|
||||
std::cout
|
||||
<< "| [1] Select gimbal mount position at NO.1 payload port |"
|
||||
<<
|
||||
std::endl;
|
||||
std::cout
|
||||
<< "| [2] Select gimbal mount position at NO.2 payload port |"
|
||||
<<
|
||||
std::endl;
|
||||
std::cout
|
||||
<< "| [3] Select gimbal mount position at NO.3 payload port |"
|
||||
<< "| [1 ~ 4] Select gimbal mount position at NO.1~NO.4 |"
|
||||
<<
|
||||
std::endl;
|
||||
std::cout
|
||||
@ -110,7 +102,7 @@ start:
|
||||
return;
|
||||
}
|
||||
|
||||
if (mountPosition > '3' || mountPosition < '1') {
|
||||
if (mountPosition > '4' || mountPosition < '1') {
|
||||
USER_LOG_ERROR("Input mount position is invalid");
|
||||
goto start;
|
||||
}
|
||||
@ -247,6 +239,7 @@ start:
|
||||
T_DjiGimbalManagerRotation rotation;
|
||||
T_DjiAircraftInfoBaseInfo baseInfo;
|
||||
E_DjiAircraftSeries aircraftSeries;
|
||||
E_DjiFcSubscriptionTopic topicOfPayloadGimablAngle;
|
||||
|
||||
returnCode = DjiGimbalManager_Init();
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
@ -288,12 +281,24 @@ start:
|
||||
}
|
||||
else if (aircraftSeries == DJI_AIRCRAFT_SERIES_M30 || aircraftSeries == DJI_AIRCRAFT_SERIES_M3 ||
|
||||
aircraftSeries == DJI_AIRCRAFT_SERIES_M3D) {
|
||||
topicOfPayloadGimablAngle = DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES;
|
||||
returnCode = DjiFcSubscription_SubscribeTopic(DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, DJI_DATA_SUBSCRIPTION_TOPIC_50_HZ, NULL);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("DjiFcSubscription_SubscribeTopic %d return %d", DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, returnCode);
|
||||
goto end;
|
||||
}
|
||||
USER_LOG_INFO("Subscribe topic DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES succefully.");
|
||||
} else if (aircraftSeries == DJI_AIRCRAFT_SERIES_M400) {
|
||||
topicOfPayloadGimablAngle = gimbalMountPosition == 1 ? DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO1 :
|
||||
gimbalMountPosition == 2 ? DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO2 :
|
||||
gimbalMountPosition == 3 ? DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO3 :
|
||||
gimbalMountPosition == 4 ? DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO4 : DJI_FC_SUBSCRIPTION_TOPIC_TOTAL_NUMBER;
|
||||
returnCode = DjiFcSubscription_SubscribeTopic(topicOfPayloadGimablAngle, DJI_DATA_SUBSCRIPTION_TOPIC_50_HZ, NULL);
|
||||
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_ERROR("DjiFcSubscription_SubscribeTopic %d return %d", DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES, returnCode);
|
||||
goto end;
|
||||
}
|
||||
USER_LOG_INFO("Subscribe topic DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES_ON_POS_NO%d succefully.", gimbalMountPosition);
|
||||
}
|
||||
|
||||
|
||||
@ -403,8 +408,8 @@ start:
|
||||
threeGimbalData.anglesData[gimbalMountPosition - 1].yaw);
|
||||
}
|
||||
else if (aircraftSeries == DJI_AIRCRAFT_SERIES_M30 || aircraftSeries == DJI_AIRCRAFT_SERIES_M3 ||
|
||||
aircraftSeries == DJI_AIRCRAFT_SERIES_M3D) {
|
||||
returnCode = DjiFcSubscription_GetLatestValueOfTopic(DJI_FC_SUBSCRIPTION_TOPIC_GIMBAL_ANGLES,
|
||||
aircraftSeries == DJI_AIRCRAFT_SERIES_M3D || aircraftSeries == DJI_AIRCRAFT_SERIES_M400) {
|
||||
returnCode = DjiFcSubscription_GetLatestValueOfTopic(topicOfPayloadGimablAngle,
|
||||
(uint8_t *) &gimbalAngles,
|
||||
sizeof(T_DjiFcSubscriptionGimbalAngles),
|
||||
×tamp);
|
||||
|
||||
@ -28,8 +28,11 @@
|
||||
#include <iostream>
|
||||
#include "dji_logger.h"
|
||||
#include "hms/test_hms.h"
|
||||
#include "dji_hms_customization.h"
|
||||
#include "dji_aircraft_info.h"
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define DJI_HMS_ERROR_NETWORK_IS_POOR (0x1E020004)
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
|
||||
@ -77,6 +80,86 @@ 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.");
|
||||
}
|
||||
|
||||
void DjiUser_RunHmsNetworkSample(void)
|
||||
{
|
||||
T_DjiOsalHandler *osalHandler = DjiPlatform_GetOsalHandler();
|
||||
char inputSelectSample;
|
||||
T_DjiReturnCode returnCode = 0;
|
||||
E_DjiEnhancedTransmissionState state = DJI_ENHANCEED_TRANSMISSION_STATE_DISABLED;
|
||||
|
||||
start:
|
||||
osalHandler->TaskSleepMs(100);
|
||||
|
||||
std::cout
|
||||
<< "\n"
|
||||
<< "| Available commands: |\n"
|
||||
<< "| [1] Get Enhanced Transmission state |\n"
|
||||
<< "| [2] send Network hms msg |\n"
|
||||
<< "| [3] clear Network hms msg |\n"
|
||||
<< "| [q] Quit |\n"
|
||||
<< std::endl;
|
||||
|
||||
std::cin >> inputSelectSample;
|
||||
switch (inputSelectSample) {
|
||||
case '1':
|
||||
DjiAircraftInfo_GetEnhancedTransmission(&state);
|
||||
goto start;
|
||||
case '2':
|
||||
returnCode = DjiHmsCustomization_InjectHmsErrorCode(DJI_HMS_ERROR_NETWORK_IS_POOR, DJI_HMS_ERROR_LEVEL_WARN);
|
||||
if (returnCode == DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_INFO("InjectHmsErrorCode success");
|
||||
} else {
|
||||
USER_LOG_ERROR("InjectHmsErrorCode fail");
|
||||
}
|
||||
goto start;
|
||||
case '3':
|
||||
returnCode = DjiHmsCustomization_EliminateHmsErrorCode(DJI_HMS_ERROR_NETWORK_IS_POOR);
|
||||
if (returnCode == DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
|
||||
USER_LOG_INFO("EliminateHmsErrorCode success");
|
||||
} else {
|
||||
USER_LOG_ERROR("EliminateHmsErrorCode fail");
|
||||
}
|
||||
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****/
|
||||
|
||||
@ -40,6 +40,8 @@ extern "C" {
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
void DjiUser_RunHmsManagerSample(void);
|
||||
void DjiUser_RunHmsEnhanceSample(void);
|
||||
void DjiUser_RunHmsNetworkSample(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
||||
0
PSDK/samples/sample_c++/module_sample/liveview/test_liveview_entry.cpp
Normal file → Executable file
0
PSDK/samples/sample_c++/module_sample/liveview/test_liveview_entry.cpp
Normal file → Executable file
@ -212,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");
|
||||
@ -243,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') {
|
||||
|
||||
@ -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;
|
||||
|
||||
@ -48,15 +48,10 @@ T_DjiReturnCode Osal_FileOpen(const char *fileName, const char *fileMode, T_DjiF
|
||||
|
||||
*fileObj = fopen(fileName, fileMode);
|
||||
if (*fileObj == NULL) {
|
||||
goto out;
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
|
||||
out:
|
||||
free(*fileObj);
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
T_DjiReturnCode Osal_FileClose(T_DjiFileHandle fileObj)
|
||||
|
||||
@ -32,6 +32,7 @@
|
||||
|
||||
/* Private constants ---------------------------------------------------------*/
|
||||
#define SOCKET_RECV_BUF_MAX_SIZE (1000 * 1000 * 10)
|
||||
#define MAX_UDP_PAYLOAD_SIZE 65507
|
||||
|
||||
/* Private types -------------------------------------------------------------*/
|
||||
typedef struct {
|
||||
@ -141,6 +142,7 @@ T_DjiReturnCode Osal_UdpSendData(T_DjiSocketHandle socketHandle, const char *ipA
|
||||
struct sockaddr_in addr;
|
||||
T_SocketHandleStruct *socketHandleStruct = (T_SocketHandleStruct *) socketHandle;
|
||||
int32_t ret;
|
||||
ssize_t total_sent = 0;
|
||||
|
||||
if (socketHandle <= 0 || ipAddr == NULL || port == 0 || buf == NULL || len == 0 || realLen == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
@ -151,13 +153,21 @@ T_DjiReturnCode Osal_UdpSendData(T_DjiSocketHandle socketHandle, const char *ipA
|
||||
addr.sin_port = htons(port);
|
||||
addr.sin_addr.s_addr = inet_addr(ipAddr);
|
||||
|
||||
ret = sendto(socketHandleStruct->socketFd, buf, len, 0, (struct sockaddr *) &addr, sizeof(struct sockaddr_in));
|
||||
if (ret >= 0) {
|
||||
*realLen = ret;
|
||||
} else {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
while (len > 0) {
|
||||
size_t chunk_size = (len > MAX_UDP_PAYLOAD_SIZE) ? MAX_UDP_PAYLOAD_SIZE : len;
|
||||
ssize_t sent = sendto(socketHandleStruct->socketFd, buf, chunk_size, 0, (struct sockaddr *) &addr, sizeof(struct sockaddr_in));
|
||||
|
||||
if (sent < 0) {
|
||||
perror("sendto failed");
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SYSTEM_ERROR;
|
||||
}
|
||||
|
||||
buf += sent;
|
||||
len -= sent;
|
||||
total_sent += sent;
|
||||
}
|
||||
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
@ -46,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 ()
|
||||
@ -133,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)
|
||||
|
||||
|
||||
@ -25,6 +25,8 @@
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <liveview/test_liveview_entry.hpp>
|
||||
#include <perception/test_perception_entry.hpp>
|
||||
#include <perception/test_lidar_entry.hpp>
|
||||
#include <perception/test_radar_entry.hpp>
|
||||
#include <flight_control/test_flight_control.h>
|
||||
#include <gimbal/test_gimbal_entry.hpp>
|
||||
#include "application.hpp"
|
||||
@ -71,6 +73,8 @@ start:
|
||||
<< "| [d] Stereo vision view sample - display the stereo image |\n"
|
||||
<< "| [e] Run camera manager sample - you can test camera's functions interactively |\n"
|
||||
<< "| [f] Start rtk positioning sample - you can receive rtk rtcm data when rtk signal is ok |\n"
|
||||
<< "| [g] Request Lidar data sample - Request Lidar data and store the point cloud data as pcd files |\n"
|
||||
<< "| [h] Request Radar data sample - Request radar data |\n"
|
||||
<< std::endl;
|
||||
|
||||
std::cin >> inputChar;
|
||||
@ -105,6 +109,12 @@ start:
|
||||
|
||||
USER_LOG_INFO("Start rtk positioning sample successfully");
|
||||
break;
|
||||
case 'g':
|
||||
DjiUser_RunLidarDataSubscriptionSample();
|
||||
break;
|
||||
case 'h':
|
||||
DjiUser_RunRadarDataSubscriptionSample();
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
@ -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,84 +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)
|
||||
else ()
|
||||
message(STATUS "Did not find OpenCV in the system, image data is inside RecvContainer as raw data")
|
||||
endif ()
|
||||
|
||||
find_package(FFMPEG REQUIRED)
|
||||
if (FFMPEG_FOUND)
|
||||
message(STATUS "Found FFMPEG installed in the system")
|
||||
message(STATUS " - Includes: ${FFMPEG_INCLUDE_DIR}")
|
||||
message(STATUS " - Libraries: ${FFMPEG_LIBRARIES}")
|
||||
|
||||
EXECUTE_PROCESS(COMMAND ffmpeg -version
|
||||
OUTPUT_VARIABLE ffmpeg_version_output
|
||||
OUTPUT_STRIP_TRAILING_WHITESPACE
|
||||
)
|
||||
string(REGEX MATCH "version.*Copyright" ffmpeg_version_line ${ffmpeg_version_output})
|
||||
string(REGEX MATCH " .* " ffmpeg_version ${ffmpeg_version_line})
|
||||
string(REGEX MATCH "^ 5.*$" ffmpeg_major_version ${ffmpeg_version})
|
||||
|
||||
if (HEAD${ffmpeg_major_version} STREQUAL "HEAD")
|
||||
message(STATUS " - Version: ${ffmpeg_version}")
|
||||
else ()
|
||||
message(FATAL_ERROR " - Not support FFMPEG version: ${ffmpeg_major_version}, please install 4.x.x instead.")
|
||||
endif ()
|
||||
|
||||
target_link_libraries(${PROJECT_NAME} ${FFMPEG_LIBRARIES})
|
||||
include_directories(${FFMPEG_INCLUDE_DIR})
|
||||
add_definitions(-DFFMPEG_INSTALLED)
|
||||
else ()
|
||||
message(STATUS "Cannot Find FFMPEG")
|
||||
endif (FFMPEG_FOUND)
|
||||
|
||||
include_directories(${CMAKE_CURRENT_LIST_DIR}/../../../../../psdk_lib/include)
|
||||
|
||||
if (BUILD_CROSS_COMPILE MATCHES TRUE)
|
||||
# Try to see if user has OpenCV installed
|
||||
# if yes, default callback will display the image
|
||||
find_package(OpenCV QUIET)
|
||||
if (OpenCV_FOUND)
|
||||
message("\n${PROJECT_NAME}...")
|
||||
message(STATUS "Found OpenCV installed in the system, will use it to display image in AdvancedSensing APIs")
|
||||
message(STATUS " - Includes: ${OpenCV_INCLUDE_DIRS}")
|
||||
message(STATUS " - Libraries: ${OpenCV_LIBRARIES}")
|
||||
add_definitions(-DOPEN_CV_INSTALLED)
|
||||
target_include_directories(${PROJECT_NAME} PRIVATE ${OpenCV_INCLUDE_DIRS})
|
||||
target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS})
|
||||
else ()
|
||||
message(STATUS "Did not find OpenCV in the system, image data is inside RecvContainer as raw data")
|
||||
endif ()
|
||||
|
||||
find_package(OPUS REQUIRED)
|
||||
if (OPUS_FOUND)
|
||||
message(STATUS "Found OPUS installed in the system")
|
||||
message(STATUS " - Includes: ${OPUS_INCLUDE_DIR}")
|
||||
message(STATUS " - Libraries: ${OPUS_LIBRARY}")
|
||||
find_package(FFMPEG REQUIRED)
|
||||
if (FFMPEG_FOUND)
|
||||
message(STATUS "Found FFMPEG installed in the system")
|
||||
message(STATUS " - Includes: ${FFMPEG_INCLUDE_DIR}")
|
||||
message(STATUS " - Libraries: ${FFMPEG_LIBRARIES}")
|
||||
|
||||
add_definitions(-DOPUS_INSTALLED)
|
||||
target_link_libraries(${PROJECT_NAME} /usr/local/lib/libopus.a)
|
||||
else ()
|
||||
message(STATUS "Cannot Find OPUS")
|
||||
endif (OPUS_FOUND)
|
||||
EXECUTE_PROCESS(COMMAND ffmpeg -version
|
||||
OUTPUT_VARIABLE ffmpeg_version_output
|
||||
OUTPUT_STRIP_TRAILING_WHITESPACE
|
||||
)
|
||||
string(REGEX MATCH "version.*Copyright" ffmpeg_version_line ${ffmpeg_version_output})
|
||||
string(REGEX MATCH " .* " ffmpeg_version ${ffmpeg_version_line})
|
||||
string(REGEX MATCH "^ 5.*$" ffmpeg_major_version ${ffmpeg_version})
|
||||
|
||||
find_package(LIBUSB REQUIRED)
|
||||
if (LIBUSB_FOUND)
|
||||
message(STATUS "Found LIBUSB installed in the system")
|
||||
message(STATUS " - Includes: ${LIBUSB_INCLUDE_DIR}")
|
||||
message(STATUS " - Libraries: ${LIBUSB_LIBRARY}")
|
||||
if (HEAD${ffmpeg_major_version} STREQUAL "HEAD")
|
||||
message(STATUS " - Version: ${ffmpeg_version}")
|
||||
else ()
|
||||
message(FATAL_ERROR " - Not support FFMPEG version: ${ffmpeg_major_version}, please install 4.x.x instead.")
|
||||
endif ()
|
||||
|
||||
add_definitions(-DLIBUSB_INSTALLED)
|
||||
target_link_libraries(${PROJECT_NAME} usb-1.0)
|
||||
else ()
|
||||
message(STATUS "Cannot Find LIBUSB")
|
||||
endif (LIBUSB_FOUND)
|
||||
target_link_libraries(${PROJECT_NAME} ${FFMPEG_LIBRARIES})
|
||||
include_directories(${FFMPEG_INCLUDE_DIR})
|
||||
add_definitions(-DFFMPEG_INSTALLED)
|
||||
else ()
|
||||
message(STATUS "Cannot Find FFMPEG")
|
||||
endif (FFMPEG_FOUND)
|
||||
|
||||
find_package(OPUS REQUIRED)
|
||||
if (OPUS_FOUND)
|
||||
message(STATUS "Found OPUS installed in the system")
|
||||
message(STATUS " - Includes: ${OPUS_INCLUDE_DIR}")
|
||||
message(STATUS " - Libraries: ${OPUS_LIBRARY}")
|
||||
|
||||
add_definitions(-DOPUS_INSTALLED)
|
||||
target_link_libraries(${PROJECT_NAME} /usr/local/lib/libopus.a)
|
||||
else ()
|
||||
message(STATUS "Cannot Find OPUS")
|
||||
endif (OPUS_FOUND)
|
||||
|
||||
find_package(LIBUSB REQUIRED)
|
||||
if (LIBUSB_FOUND)
|
||||
message(STATUS "Found LIBUSB installed in the system")
|
||||
message(STATUS " - Includes: ${LIBUSB_INCLUDE_DIR}")
|
||||
message(STATUS " - Libraries: ${LIBUSB_LIBRARY}")
|
||||
|
||||
add_definitions(-DLIBUSB_INSTALLED)
|
||||
target_link_libraries(${PROJECT_NAME} usb-1.0)
|
||||
else ()
|
||||
message(STATUS "Cannot Find LIBUSB")
|
||||
endif (LIBUSB_FOUND)
|
||||
endif ()
|
||||
|
||||
if (NOT EXECUTABLE_OUTPUT_PATH)
|
||||
set(EXECUTABLE_OUTPUT_PATH ${CMAKE_BINARY_DIR}/bin)
|
||||
endif ()
|
||||
|
||||
target_link_libraries(${PROJECT_NAME} m)
|
||||
target_link_libraries(${PROJECT_NAME} dl)
|
||||
|
||||
add_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 ()
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
|
||||
@ -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 ------------------------------------------------------------*/
|
||||
|
||||
|
||||
@ -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****/
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
|
||||
@ -255,6 +255,18 @@ T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *stat
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo)
|
||||
{
|
||||
if (deviceInfo == NULL) {
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_INVALID_PARAMETER;
|
||||
}
|
||||
|
||||
deviceInfo->vid = USB_UART_CONNECTED_TO_UAV_VID;
|
||||
deviceInfo->pid = USB_UART_CONNECTED_TO_UAV_PID;
|
||||
|
||||
return DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS;
|
||||
}
|
||||
|
||||
/* Private functions definition-----------------------------------------------*/
|
||||
|
||||
/****************** (C) COPYRIGHT DJI Innovations *****END OF FILE****/
|
||||
|
||||
@ -48,6 +48,15 @@ extern "C" {
|
||||
#define LINUX_UART_DEV1 "/dev/ttyUSB0"
|
||||
#define LINUX_UART_DEV2 "/dev/ttyACM0"
|
||||
|
||||
/**
|
||||
* Use for Eport 2.0, specify the VID and PID of the USB serial port closest to the aircraft.
|
||||
* FT232 0x0403:0x6001
|
||||
* CP2102 0x10C4:0xEA60
|
||||
* VCOM 0x2CA3:0xF002
|
||||
*/
|
||||
#define USB_UART_CONNECTED_TO_UAV_VID (0x0403)
|
||||
#define USB_UART_CONNECTED_TO_UAV_PID (0x6001)
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
|
||||
/* Exported functions --------------------------------------------------------*/
|
||||
@ -56,6 +65,7 @@ T_DjiReturnCode HalUart_DeInit(T_DjiUartHandle uartHandle);
|
||||
T_DjiReturnCode HalUart_WriteData(T_DjiUartHandle uartHandle, const uint8_t *buf, uint32_t len, uint32_t *realLen);
|
||||
T_DjiReturnCode HalUart_ReadData(T_DjiUartHandle uartHandle, uint8_t *buf, uint32_t len, uint32_t *realLen);
|
||||
T_DjiReturnCode HalUart_GetStatus(E_DjiHalUartNum uartNum, T_DjiUartStatus *status);
|
||||
T_DjiReturnCode HalUart_GetDeviceInfo(T_DjiHalUartDeviceInfo *deviceInfo);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
||||
@ -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;
|
||||
}
|
||||
|
||||
|
||||
@ -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 ------------------------------------------------------------*/
|
||||
|
||||
Reference in New Issue
Block a user