Flight Control
Overview
Using the aircraft flight control function of PSDK, you can set and obtain various basic parameters of the aircraft, control the aircraft to perform basic flight actions, and control the aircraft to perform complex flight actions through the Joystick function.
Basic Concepts
Aircraft basic information
PSDK opens an interface for setting the basic parameters of the aircraft. By setting and obtaining the basic parameters of the aircraft, developers can achieve precise control of the aircraft:
- Enable or disable RTK function and obstacle sensing function (horizontal obstacle sensing and upward obstacle sensing and downward obstacle sensing).
- Set the home point and return altitude of the aircraft.
- Set lost behavior on Matrice 30/30T, Mavic 3 Enterprise Series.
- Obtain the Country codesof the aircraft, adapting your product to different national regulatory requirements.
An application with the function of Information Management can facilitate users to obtain information about the basic parameters of the aircraft:
- Get the status of RTK function and obstacle sensing function (horizontal obstacle sensing and upward obstacle sensing and downward obstacle sensing)
- Get the home point and return altitude of the aircraft
Basic aircraft flight action
The basic flight actions of the aircraft mainly include three categories: aircraft locking, aircraft take-off and landing, and aircraft return. Developers can use the interface provided by PSDK to control the aircraft to execute the specified operation according to the actual control requirements. flight action.
Table. Basic flight maneuvers
function type | basic skills | function description |
---|---|---|
aircraft lock | unlock | After the aircraft is unlocked, the aircraft's propellers will spin at idle speed, but will not fly off the ground |
locked | After the aircraft is locked, the propeller of the aircraft changes from an idle rotating state to a stationary state | |
takeoff and landing | automatic takeoff | When using this function, the aircraft will automatically take off 1.2 meters (this height cannot be adjusted) |
automatic landing | When using this function, the aircraft will automatically land | |
Cancel automatic landing | When using this function, the aircraft will stop landing and hover in the air during the descent | |
Landing confirmation | When the aircraft has landed to a certain distance from the ground, the user can use this function to confirm that the aircraft has landed on the ground | |
forced landing | Ignore the status of the landing surface and force the aircraft to land (the landing speed is faster) | |
go home | go home | When using this function, the aircraft will automatically return to home |
cancel go home | When using this feature, the aircraft hovers in the air |
Notes:
- Different models of aircraft may have different heights when performing take-off, landing and return operations. For details, please refer to the instruction manual of the optional model.
- After the aircraft is unlocked, if the take-off command is not received, the aircraft will automatically lock and the propeller will stop rotating. If the aircraft fails to unlock, please check the reason for the failure according to the error code.
Joystick function
Joystick is a comprehensive control function for aircraft. When using the Joystick function, the developer can set the coordinate system used by the aircraft, the horizontal control mode, and the vertical control mode by calling the interface in the Joystick according to the actual application needs. Mode, yaw angle control mode and hover mode**, can design the aircraft flight control logic that meets the needs of use.
Set coordinate system
Body coordinate system The body coordinate system takes the center of gravity of the aircraft as the origin, the forward direction of the aircraft head is the X axis, the right side of the forward direction of the nose is the Y axis. The Z axis is the axis that intersects perpendicularly with the X axis and Y axis at the center of gravity and points downward of the aircraft (following the "Right Hand Rule"). In the body coordinates, the flight action of the aircraft when it rotates around the X, Y and Z axes can be called roll (the aircraft only rotates around the X axis), pitch (the aircraft only rotates around the Y axis) and yaw (the aircraft only rotates around the Z axis).
Geodetic coordinate system The geodetic coordinate system is also called the world coordinate system or the local horizontal coordinate system. In this coordinate system, the direction of the aircraft pointing to the true north of the earth is the X-axis, the direction of the true east is the Y-axis, the X-axis and the Y-axis are perpendicular to each other, and the Z-axis is perpendicular to each other. The axis points vertically below the aircraft. On the premise of satisfying the "right-hand rule", the Z-axis will adjust the angle according to the actual situation of the aircraft's flight, so this coordinate system is also called "North-East-Earth (NED) coordinates. Tie".
Set horizontal control mode
- Attitude angle control mode: In this mode, the command in the horizontal direction is the attitude angle of the aircraft. (In the body coordinate system, the angle is roll and pitch)
- Speed control mode: In this mode, the command in the horizontal direction is the speed of the aircraft
- Position control mode: In this mode, the command in the horizontal direction is the position of the aircraft
Note: When the modulo of the position command is not 0, the aircraft will fly forward at the specified speed, otherwise, the aircraft will hover at the specified position.
- Angular velocity control: In this mode, the command in the horizontal direction is the rotational angular velocity of the aircraft
Set the aircraft hover mode
Only in the speed control mode in the **horizontal control mode, the developer can set the hovering mode of the aircraft:
- Turn on stable mode: After turning on stable mode, the aircraft will hover at the specified position
- Turn off the stable mode: After turning off the stable mode, the aircraft will fly according to the speed command. When the forward speed of the aircraft is 0, the aircraft may flutter with the wind
Set vertical control mode
- Speed control mode: control the speed of the aircraft in the vertical direction
- Position control mode: control the vertical position of the aircraft, which is an absolute position relative to the take-off point
- Throttle control mode: Control the throttle of the aircraft
Set yaw angle control mode
- Angle control mode: In this mode, the command to rotate in the yaw direction is the angle of the yaw
- Angular rate control mode: In this mode, the command to rotate in the yaw direction is the angular rate of yaw
aircraft altitude
The basic concept of altitude for DJI's aircraft during flight missions is shown in Table. The concept of aircraft altitude.
Table. aircraft altitude description
relative takeoff altitude | fusion height | GPS altitude | RTK altitude | height above ground | |
---|---|---|---|---|---|
basic meaning | The altitude change of the aircraft relative to the take-off point | Using the barometer value as the initial value, use the fusion algorithm to output the altitude value with the help of the data from all the sensors on the aircraft | Real-time ellipsoid height based on GPS satellite output | Real-time ellipsoid height output based on RTK technology | The distance between the aircraft and the object currently below, obtained by the ranging sensor on the aircraft |
Data Sources | IMU (may include vision sensors, GPS and RTK) and barometer | IMU (may include vision sensors, GPS and RTK) and barometer | GPS satellite | RTK satellite | TOF or Ultrasound and IMU |
height 0 points | The point where the aircraft takes off from the ground | sea level at standard pressure | WGS84 Coordinate System | RTK coordinate system (C2000, WGS84 or user-specified coordinate system) | A solid surface (such as the ground) directly below the aircraft |
Scenario | Used to get the current altitude of the aircraft | For more precise and stable control of aircraft to perform flight tasks | Used to analyze the flight mission and flight status of the aircraft | For precision mapping and waypoint flight missions | Used for safe landing of the aircraft (obstacle avoidance and deceleration) |
Valid range | Thousands of meters | Thousands of meters | Thousands of meters | Thousands of meters | Within 10 meters |
Get method | Get this information through DJI Pilot The Mobile App developed based on MSDK can subscribe to this information | Mobile App developed based on MSDK can subscribe to this information | Mobile App developed based on MSDK can subscribe to this information | Mobile App developed based on MSDK can subscribe to this information | Get this information through DJI Pilot The Mobile App developed based on MSDK can subscribe to this information |
Data error | Yes, the altitude accuracy will be affected by the flying distance of the aircraft | Yes, the altitude accuracy will be affected by the flying distance of the aircraft | none | none | none |
Reliability | Unreliable | Unreliable | Basically reliable | Reliable | Reliable |
Error (noise) level | Low | Low | High | Low | Low |
Factors | Affected by temperature, humidity, air pressure | Affected by temperature, humidity, air pressure | Affected by the strength of GPS satellites, the short-term error is large, and the long-term error is relatively small | Influenced by the working state of RTK satellites and the accuracy of RTK base stations, the overall error is small | Properties (such as texture and texture) of hard surfaces directly below the aircraft |
Control Authority Introduction
Before invoking the aircraft control interface, you need to invoke the DjiFlightController_ObtainJoystickCtrlAuthority
interface to gain control authority over the aircraft. Until the control authority over the aircraft becomes effective, the aircraft control command interfaces will not have any effect.
Control Authority: This refers to the current permission to control the aircraft. The controlling owner have MSDK, PSDK, the remote controller, and DJI Dock. Control authority allows to be taken and released.
Fail-Safe Behavior: In cases where the aircraft enters an uncontrollable state due to various unexpected factors during control (such as remote controller disconnection, PSDK program crashes, low battery, etc.), it enters a fail-safe mode. In this mode, the control authority over the aircraft may change (on certain models), and corresponding pre-set fail-safe behaviors are executed (such as return to home, landing, hovering).
M300 RTK/M350 RTK Control Logic
Scenarios for Active Control Authority Switching:
- PSDK actively releases control authority.
- The remote controller switches flight gears.
- The remote controller triggers return-to-home.
- The remote controller activates pause.
Scenarios for Passive Control Authority Switching:
- Low battery triggering return-to-home/landing.
- PSDK losing connection abnormally.
Table. M300 RTK/M350 RTK Controlling Logic
RC State | Control Authority State | Abnormal Scenario | Expected executing Strategy |
---|---|---|---|
Connected | PSDK | RC is disconnected | No Strategy |
Connected | PSDK | PSDK is disconnected | Following the parameter strategy of DA2 (not switching SDK when remote control is lost), the pre-set fail-safe behavior configured on DA2 will be executed upon activation, without switching control authority. |
Connected | RC | RC is disconnected | Execute lost behavior set in App of RC |
Connected | RC | PSDK is disconnected | No Strategy |
Disconnected | PSDK | PSDK is disconnected (programme crashes or hardware disconnected) | Following the parameter strategy of DA2 (not switching SDK when remote control is lost), the pre-set fail-safe behavior configured on DA2 will be executed upon activation, without switching control authority. |
Disconnected | PSDK | RC reconnected | No Strategy |
Disconnected | PSDK | Triggered obstacle sensing | Execute pre-set obstacle avoidance behavior, without switching control authority. |
Disconnected | PSDK | Low battery return/landing | Execute pre-set low battery behavior, without switching control authority. |
Disconnected | PSDK | Approach Restricted Zones | Can not enter the Restricted Zones. No response to the Joystick action. Need to execute return to home. |
Disconnected | PSDK | RTK/GPS signal lost | Visual hovering. If the vision is lost, aircraft will move. |
M30/M30T/M3E/M3T Control Logic
Scenarios for Active Control Authority Switching:
- PSDK actively releases control authority.
- The remote controller switches flight gears.
- The remote controller triggers return-to-home.
- The remote controller activates pause.
Scenarios for Passive Control Authority Switching:
- Low battery triggering return-to-home/landing.
- Abnormal PSDK disconnection.
Table. M30/M30T/M3e/m3T Controlling Logic
RC State | Control Authority State | Abnormal Scenario | Expected executing Strategy |
---|---|---|---|
Connected | PSDK | RC is disconnected | No Strategy |
Connected | PSDK | PSDK is disconnected | Switch the control authority. Execute the lost behavior set on PSDK (behavior is the same on APP) |
Connected | RC | RC is disconnected | Execute lost behavior set in App of RC |
Connected | RC | PSDK is disconnected | No Strategy |
Disconnected | PSDK | PSDK is disconnected | Switch the control authority. Execute the lost behavior set on PSDK (behavior is the same on APP) |
Disconnected | PSDK | RC reconnected | No Strategy |
Disconnected | PSDK | Triggered obstacle sensing | Execute pre-set obstacle avoidance behavior, without switching control authority. |
Disconnected | PSDK | Approach Restricted Zones | Can not enter the Restricted Zones and switch the control authority. No response to the Joystick action. Need to execute return to home. |
Disconnected | PSDK | Low battery return/landing | Execute pre-set low battery behavior and switch control authority. |
Disconnected | PSDK | RTK/GPS signal lost | Visual hovering. If the vision is lost, aircraft will move. |
Using the flight controls
To use the aircraft flight control function, you need to initialize the flight control module first, then set the basic parameters of the aircraft, and finally use the functions in the Joystick.
When controlling the aircraft using PSDK without the remote controller, it's essential to subscribe to key data from the aircraft and rigorously check the current state of the aircraft to determine if it allows for flight control. You have to examine critical flight parameters such as current battery level, return-to-home point, fail-safe behavior, RTK switch, obstacle sensing switch, and more. Additionally, strict compliance with local aircraft regulations is required. For instance, in the United States, reporting RID information is mandatory, or it can result in the aircraft being prevented from flying. Third-party developers must ensure the accuracy of RID information.
During the flight mission, real-time monitoring of the aircraft's status and alert information is necessary to assist remote pilots or program decisions. Refer to the Information Management and HMS Features chapter for further details.
1. Initialize the flight control module
Before using the related interfaces of the flight control function, you need to call the DjiTest_FlightControlInit
interface to initialize the flight control module.
returnCode = DjiTest_FlightControlInit(ridInfo);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Init flight Control sample failed,error code:0x%08llX", returnCode);
return returnCode;
}
2. Gain control of the aircraft
Before calling the aircraft control interface, you need to call the DjiFlightController_ObtainJoystickCtrlAuthority
interface to obtain the control authority of the aircraft. Before the aircraft control authority takes effect, the aircraft control command interface will not take effect.
returnCode = DjiFlightController_ObtainJoystickCtrlAuthority();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Obtain joystick authority failed, error code: 0x%08X", returnCode);
goto out;
}
s_osalHandler->TaskSleepMs(1000);
3. Get and set aircraft parameters
Before controlling the automatic flight of the aircraft, it is necessary to check and set the relevant parameters of the aircraft. The flight control module provides a series of Set and Get interfaces, which can obtain and set the aircraft parameters and take effect in real time.
/*! Turn on horizontal vision avoid enable */
USER_LOG_INFO("--> Step 1: Turn on horizontal visual obstacle avoidance");
DjiTest_WidgetLogAppend("--> Step 1: Turn on horizontal visual obstacle avoidance");
returnCode = DjiFlightController_SetHorizontalVisualObstacleAvoidanceEnableStatus(
DJI_FLIGHT_CONTROLLER_ENABLE_OBSTACLE_AVOIDANCE);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Turn on horizontal visual obstacle avoidance failed, error code: 0x%08X", returnCode);
goto out;
};
s_osalHandler->TaskSleepMs(1000);
USER_LOG_INFO("--> Step 2: Get horizontal horizontal visual obstacle status\r\n");
DjiTest_WidgetLogAppend("--> Step 2: Get horizontal horizontal visual obstacle status\r\n");
returnCode = DjiFlightController_GetHorizontalVisualObstacleAvoidanceEnableStatus(
&horizontalVisualObstacleAvoidanceStatus);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Get horizontal visual obstacle avoidance failed, error code: 0x%08X", returnCode);
goto out;
}
USER_LOG_INFO("Current horizontal visual obstacle avoidance status is %d\r\n",
horizontalVisualObstacleAvoidanceStatus);
s_osalHandler->TaskSleepMs(1000);
/*! Turn on horizontal radar avoid enable */
USER_LOG_INFO("--> Step 3: Turn on horizontal radar obstacle avoidance");
DjiTest_WidgetLogAppend("--> Step 3: Turn on horizontal radar obstacle avoidance");
returnCode = DjiFlightController_SetHorizontalRadarObstacleAvoidanceEnableStatus(
DJI_FLIGHT_CONTROLLER_ENABLE_OBSTACLE_AVOIDANCE);
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Turn on horizontal radar obstacle avoidance failed, error code: 0x%08X", returnCode);
goto out;
};
s_osalHandler->TaskSleepMs(1000);
4. Control the aircraft to perform basic flight actions
Using the interface provided by PSDK, the developer can control the aircraft to perform the specified flight action according to the actual control requirements. Considering the safety of flight control, it is recommended to subscribe the relevant aircraft parameters through data subscription for closed-loop inspection and control to ensure the correct execution of flight actions.
T_DjiReturnCode djiStat;
//! Start takeoff
djiStat = DjiFlightController_StartTakeoff();
if (djiStat != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Request to take off failed, error code: 0x%08X", djiStat);
return false;
}
//! Motors start check
if (!DjiTest_FlightControlMotorStartedCheck()) {
USER_LOG_ERROR("Takeoff failed. Motors are not spinning.");
return false;
} else {
USER_LOG_INFO("Motors spinning...");
}
//! In air check
if (!DjiTest_FlightControlTakeOffInAirCheck()) {
USER_LOG_ERROR("Takeoff failed. Aircraft is still on the ground, but the "
"motors are spinning");
return false;
} else {
USER_LOG_INFO("Ascending...");
}
//! Finished takeoff check
if (!takeoffFinishedCheck()) {
USER_LOG_ERROR("Takeoff finished, but the aircraft is in an unexpected mode. "
"Please connect DJI GO.");
return false;
}
5. Using the functions in Joystick
To use the Joystick function, you need to set the Joystick mode and corresponding control commands first, and then execute the Joystick commands to control the aircraft. The following code is to use the Joystick function to control the aircraft to move to the specified position in the horizontal and vertical directions.
- Set the mode of the joystick
T_DjiFlightControllerJoystickMode joystickMode = {
DJI_FLIGHT_CONTROLLER_HORIZONTAL_POSITION_CONTROL_MODE,
DJI_FLIGHT_CONTROLLER_VERTICAL_POSITION_CONTROL_MODE,
DJI_FLIGHT_CONTROLLER_YAW_ANGLE_CONTROL_MODE,
DJI_FLIGHT_CONTROLLER_HORIZONTAL_GROUND_COORDINATE,
DJI_FLIGHT_CONTROLLER_STABLE_CONTROL_MODE_ENABLE,
};
DjiFlightController_SetJoystickMode(joystickMode);
Note: If you do not change the settings in the Joystick during the flight of the aircraft, you can only set the Joystick mode when the aircraft starts to fly.
- Set up Joystick control commands and perform Joystick functions
Note: The z-axis position in
joystickCommand
is the absolute height relative to the height of the take-off point.
while (elapsedTimeInMs < timeoutInMilSec) {
T_DjiFcSubscriptionPositionFused currentGPSPosition = DjiTest_FlightControlGetValueOfPositionFused();
T_DjiFcSubscriptionQuaternion currentQuaternion = DjiTest_FlightControlGetValueOfQuaternion();
dji_f32_t currentHeight = DjiTest_FlightControlGetValueOfRelativeHeight();
if (originHeightBaseHomePoint == -1) {
USER_LOG_ERROR("Relative height is invalid!");
return false;
}
float yawInRad = DjiTest_FlightControlQuaternionToEulerAngle(currentQuaternion).z;
//! get the vector between aircraft and origin point.
T_DjiTestFlightControlVector3f localOffset = DjiTest_FlightControlLocalOffsetFromGpsAndFusedHeightOffset(
currentGPSPosition,
originGPSPosition,
currentHeight,
originHeightBaseHomePoint);
//! get the vector between aircraft and target point.
T_DjiTestFlightControlVector3f offsetRemaining = DjiTest_FlightControlVector3FSub(offsetDesired, localOffset);
T_DjiTestFlightControlVector3f positionCommand = offsetRemaining;
DjiTest_FlightControlHorizCommandLimit(speedFactor, &positionCommand.x, &positionCommand.y);
T_DjiFlightControllerJoystickCommand joystickCommand = {positionCommand.x, positionCommand.y, offsetDesired.z + originHeightBaseHomePoint, yawDesiredInDeg};
DjiFlightController_ExecuteJoystickAction(joystickCommand);
if (DjiTest_FlightControlVectorNorm(offsetRemaining) < posThresholdInM &&
fabs(yawInRad / s_degToRad - yawDesiredInDeg) < yawThresholdInDeg) {
//! 1. We are within bounds; start incrementing our in-bound counter
withinBoundsCounter += cycleTimeInMs;
} else {
if (withinBoundsCounter != 0) {
//! 2. Start incrementing an out-of-bounds counter
outOfBounds += cycleTimeInMs;
}
}
//! 3. Reset withinBoundsCounter if necessary
if (outOfBounds > outOfControlBoundsTimeLimit) {
withinBoundsCounter = 0;
outOfBounds = 0;
}
//! 4. If within bounds, set flag and break
if (withinBoundsCounter >= withinControlBoundsTimeReqmt) {
break;
}
s_osalHandler->TaskSleepMs(cycleTimeInMs);
elapsedTimeInMs += cycleTimeInMs;
}
while (brakeCounter < withinControlBoundsTimeReqmt) {
s_osalHandler->TaskSleepMs(cycleTimeInMs);
brakeCounter += cycleTimeInMs;
}
if (elapsedTimeInMs >= timeoutInMilSec) {
USER_LOG_ERROR("Task timeout!");
return false;
}
6. Release the aircraft control
After completing a series of controls on the aircraft, you need to call DjiFlightController_ReleaseJoystickCtrlAuthority
to release the control of the aircraft so that other devices can take over the control of the aircraft.
returnCode = DjiFlightController_ReleaseJoystickCtrlAuthority();
if (returnCode != DJI_ERROR_SYSTEM_MODULE_CODE_SUCCESS) {
USER_LOG_ERROR("Release joystick authority failed, error code: 0x%08X", returnCode);
goto out;
}