public class

DJIWaypoint

extends Object
java.lang.Object
   ↳ dji.sdk.missionmanager.DJIWaypoint

Class Overview

The class represents a target point in the waypoint mission. For a waypoint mission, a flight route consists of multiple DJIWaypoint objects. User can also define the actions to perform for each DJIWaypoint.

Summary

Nested Classes
class DJIWaypoint.DJIWaypointAction This class represents a waypoint action for DJIWaypoint. 
enum DJIWaypoint.DJIWaypointActionType Waypoint action types. 
enum DJIWaypoint.DJIWaypointTurnMode How the aircraft will turn at a waypoint to transition between headings. 
Constants
int DJI_MAX_ACTION_COUNT Maximum number of actions a single waypoint can have.
int DJI_MAX_ACTION_REPEAT_TIMES Maximum number of times a single waypoint action can be repeated.
Fields
public int actionRepeatTimes Dictates how many times the set of waypoint actions are repeated.
public short actionTimeoutInSeconds The maximum time set to excute all the waypoint actions for a waypoint.
public float altitude Altitude of the aircraft in meters when it reaches waypoint.
public float cornerRadiusInMeters Corner radius of the waypoint.
public float gimbalPitch Gimbal pitch angle when reached this waypoint.
public boolean hasAction A flag to indicate whether there are any actions to be carried out at the waypoint.
public short heading Heading the aircraft will rotate to by the time it reaches the waypoint.
public double latitude Waypoint coordinate latitude in degrees.
public double longitude Waypoint coordinate longitude in degrees.
public float shootPhotoDistanceInterval The distance interval in meters when two photos are taken as the aircraft moves between the current waypoint and the next waypoint.
public float shootPhotoTimeInterval The time interval in seconds when two photos are taken as the aircraft moves between the current waypoint and the next waypoint.
public float speed The base automatic speed of the aircraft as it moves between this waypoint and the next waypoint with range [0, 15] m/s.
public DJIWaypoint.DJIWaypointTurnMode turnMode Determines whether the aircraft will turn clockwise or anti-clockwise when changing its heading.
public List<DJIWaypoint.DJIWaypointAction> waypointActions Array of all waypoint actions for the respective waypoint.
Public Constructors
DJIWaypoint(double latitude, double longitude, float altitude)
Construct instance with specific waypoint.
Public Methods
boolean addAction(DJIWaypoint.DJIWaypointAction action)
Adds a waypoint action to a waypoint.
boolean adjustActionAtIndex(int index, DJIWaypoint.DJIWaypointAction action)
Switches the action at the specified index.
DJIWaypoint.DJIWaypointAction getActionAtIndex(int index)
Gets the action at the specified index.
boolean insertAction(DJIWaypoint.DJIWaypointAction action, int index)
Insert a waypoint action at index.
boolean removeAction(DJIWaypoint.DJIWaypointAction action)
Removes the waypoint action from the waypoint.
boolean removeActionAtIndex(int index)
Removes a waypoint action from the waypoint by index.
void removeAllAction()
Remove all the actions.
[Expand]
Inherited Methods
From class java.lang.Object

Constants

public static final int DJI_MAX_ACTION_COUNT

Maximum number of actions a single waypoint can have. Currently, the maximum number supported is 15.

Constant Value: 15 (0x0000000f)

public static final int DJI_MAX_ACTION_REPEAT_TIMES

Maximum number of times a single waypoint action can be repeated. Currently, the maximum number supported is 15.

Constant Value: 15 (0x0000000f)

Fields

public int actionRepeatTimes

Dictates how many times the set of waypoint actions are repeated. The default value is one time.

public short actionTimeoutInSeconds

The maximum time set to excute all the waypoint actions for a waypoint. If the time, while executing the waypoint actions, goes above the time set, the aircraft will stop executing the waypoint actions for the current waypoint and will move on to the next waypoint. The value of this property must be in the range of [0, 999] seconds. The default value is 60 seconds.

public float altitude

Altitude of the aircraft in meters when it reaches waypoint. The altitude of the aircraft is relative to the ground at the take-off location, has a range of [-200,500] and should not be larger than the aircraft's max limited altitude. If two adjacent waypoints have different alitutdes, then the alitude will gradually change as the aircraft flies between waypoints.

public float cornerRadiusInMeters

Corner radius of the waypoint. When the flight path mode is DJIWaypointMissionFlightPathCurved the flight path near a waypoint will be a curve (rounded corner) with radius [0.2,1000]. When there is a corner radius, the aircraft will never go through the waypoint. By default, the radius is 0.2 m. The radius should not be larger than the three dimensional distance between any two of the three waypoints which make the corner.

public float gimbalPitch

Gimbal pitch angle when reached this waypoint. Property is used when DJIWaypointMission.rotateGimbalPitch is true. Value should in range [-90, 0] degrees.

public boolean hasAction

A flag to indicate whether there are any actions to be carried out at the waypoint.

public short heading

Heading the aircraft will rotate to by the time it reaches the waypoint. The aircraft heading will gradually change between two waypoints with different headings if the waypoint mission's headingMode is set to DJIWaypointMissionHeadingUsingWaypointHeading. Heading has a range of [-180, 180] degrees, where 0 represents True North.

public double latitude

Waypoint coordinate latitude in degrees.

public double longitude

Waypoint coordinate longitude in degrees.

public float shootPhotoDistanceInterval

The distance interval in meters when two photos are taken as the aircraft moves between the current waypoint and the next waypoint. The first photo is taken at the first waypoint. The maximum value is 6,000.0. The minimum value is above 0.0 and depends on the camera type, the camera parameters and the flight speed. When the photo file format is JPEG, the time interval between two photos cannot smaller than 2 seconds. When the photo file format is RAW, the time interval between two photos cannot smaller than 10 seconds for all cameras except those on the Inspire 2 which can be 5 seconds. If the input exceeds the camera's capability, the taken photos may be less than expectation. The default value is 0.0 and no photo will be taken. For a waypoint, either `shootPhotoTimeInterval` or `shootPhotoDistanceInterval` is 0.0. Input with precision of greater than 1 decimal places, will be rounded to 1. Warning: `speed`, `shootPhotoTimeInterval` and `shootPhotoDistanceInterval` relate to behavior between this waypoint and the next waypoint in the mission. In comparison, `turnMode`, `altitude` and `heading` relate to behavior between the last waypoint and this waypoint in the waypoint mission. Only supported by flight controller firmware 3.2.10.0 or above.

public float shootPhotoTimeInterval

The time interval in seconds when two photos are taken as the aircraft moves between the current waypoint and the next waypoint. The first photo will be taken as the aircraft leaves the current waypoint. The maximum value is 6,000.0. The minimum value is above 0.0 and depends on the camera type and the camera parameters. When the photo file format is JPEG, the recommended minimum value is 2.0. When the photo file format is RAW, the time interval between two photos cannot smaller than 10 seconds for all cameras except those on the Inspire 2 which can be 5 seconds. If the input exceeds the camera's capability, the pictures will be taken at the maximum possible speed. The default value is 0.0 and no photo will be taken. For a waypoint, either `shootPhotoTimeInterval` or `shootPhotoDistanceInterval` is 0.0. Input with precision of greater than 1 decimal places, will be rounded to 1. Warning: `speed`, `shootPhotoTimeInterval` and `shootPhotoDistanceInterval` relate to behavior between this waypoint and the next waypoint in the mission. In comparison, `turnMode`, `altitude` and `heading` relate to behavior between the last waypoint and this waypoint in the waypoint mission. Only supported by flight controller firmware 3.2.10.0 or above.

public float speed

The base automatic speed of the aircraft as it moves between this waypoint and the next waypoint with range [0, 15] m/s. By default, it is 0.0 and the aircraft will fly with `autoFlightSpeed` of the waypoint mission. If greater than 0, `speed` will override `autoFlightSpeed`. This `speed` can only define movement forward through the waypoint mission in comparison to `autoFlightSpeed` which can be both forward and backwards through a waypoint mission. Waypoint mission speed priority from highest to lowest is: 1) manual speed adjustment with remote controller joy sticks 2) `speed` 3) `setAutoFlightSpeed` 4) `autoFlightSpeed` Warning: `speed`, `shootPhotoTimeInterval` and `shootPhotoDistanceInterval` relate to behavior between this waypoint and the next waypoint in the mission. In comparison, `turnMode`, `altitude` and `heading` relate to behavior between the last waypoint and this waypoint in the waypoint mission. Only supported by flight controller firmware 3.2.10.0 or above.

public DJIWaypoint.DJIWaypointTurnMode turnMode

Determines whether the aircraft will turn clockwise or anti-clockwise when changing its heading.

public List<DJIWaypoint.DJIWaypointAction> waypointActions

Array of all waypoint actions for the respective waypoint. The waypoint actions will be executed consecutively from the start of the array once the aircraft reaches the waypoint.

Public Constructors

public DJIWaypoint (double latitude, double longitude, float altitude)

Construct instance with specific waypoint.

Parameters
latitude The latitude of the waypoint.
longitude The longitude of the waypoint.
altitude The altitude of the waypoint.

Public Methods

public boolean addAction (DJIWaypoint.DJIWaypointAction action)

Adds a waypoint action to a waypoint. The number of waypoint actions should not be larger than DJIMaxActionCount. The action will only be executed when the mission's flightPathMode property is set to DJIWaypointMissionFlightPathNormal and will be not be executed when the mission's flightPathMode property is set to DJIWaypointMissionFlightPathCurved. The maximum number of DJIWaypointAction you can add is 15.

Parameters
action Waypoint action to be added to the waypoint.
Returns
  • true if the waypoint action has been added to the waypoint. false if the waypoint action count is too high, or if the waypoint action was incorrectly setup.

public boolean adjustActionAtIndex (int index, DJIWaypoint.DJIWaypointAction action)

Switches the action at the specified index.

Parameters
index The specified index.
action A DJIWaypointAction object.

public DJIWaypoint.DJIWaypointAction getActionAtIndex (int index)

Gets the action at the specified index.

Parameters
index The specified index.

public boolean insertAction (DJIWaypoint.DJIWaypointAction action, int index)

Insert a waypoint action at index.

Parameters
action Waypoint action to be inserted to the waypoint.
index Index of the inserted action
Returns
  • true if the waypoint action has been inserted. false if the waypoint action count is too high or index is invalid.

public boolean removeAction (DJIWaypoint.DJIWaypointAction action)

Removes the waypoint action from the waypoint.

Parameters
action Waypoint action to be removed from the waypoint.
Returns
  • true if the waypoint action has been removed from the waypoint.

public boolean removeActionAtIndex (int index)

Removes a waypoint action from the waypoint by index. After removal, all actions higher in the index will be shifted down by one.

Parameters
index Waypoint action to be removed at index.
Returns
  • true if the waypoint action has been removed from the waypoint.

public void removeAllAction ()

Remove all the actions.