class PathMission
Description: Waypoint mission, mainly contains the number of waypoints, coordinates of the home point, specific information of the waypoint.
public class PathMission {
/**
* number of waypoints
*/
public short WPNum;
/**
* whether to use the default radius. Values: 0: no, 1: yes
*/
public short default_R_flag;
/**
* coordinate of Home point
*/
public double[] HomeLLA;//3
/**
* number of pieces of waypoint information (500)
*/
public PathPoint[] WP_Info_strc;//500
}
class PathPoint
Description: Sets the waypoint information including the coordinate, flight attitude, camera actions, and POIs.
public class PathPoint {
/** Waypoint type: 1: waypoint where the aircraft will stop, 2: waypoint where the aircraft will turns ahead before reaching it */
public short WPTypeUsr;
/** User-defined waypoint, longitude, latitude, and height */
public double[] WPLLAUsr;//3
/** User-defined turning radius*/
public double RadUsr;
/** Speed */
public double VelRefUsr;
/** Waypoint altitude priority 1: indicates that the priority of this waypoint is higher than the previous waypoint, -1: indicates that the priority of this waypoint is lower than the previous waypoint, 0: there is no priority */
public short AltPrioUsr;
/** Heading mode at this waypoint 1: coordinated turn mode, 2: manual, 3: custom mode */
public short Heading_Mode;
/** Whether a POI exists -1: no POI exists, 1: there is a POI*/
public short POI_Valid;
/** Coordinate of the POI, longitude, latitude, and height */
public double[] POIUsr;//3
/** Total number of camera actions at this waypoint */
public short ActionNum;
/** Number of camera actions at this waypoint. The maximum number is 10. */
public CameraActionJNI[] MSN_ActionInfo;//10
}
class CameraActionJNI
Description: Sets the camera actions during waypoint flight.
public class CameraActionJNI {
/** Action type */
public int Action_Type;
/** Pitch angle of the gimbal */
public float Gimbal_Pitch;
/** Roll angle of the gimbal */
public float Gimbal_Roll;
/** Yaw angle of the gimbal */
public float Action_Yaw_Ref;
/** Interval between periodic shoots (s) */
public int Shoot_Time_Interval;
/** Distance for fixed-distance photography (mm) */
public float Shoot_Dis_Interval;
/** Action execution time (s) */
public int Action_Time;
/** zoom factor */
public int Zoom_Rate;
/** Reserved */
public int[] reserved;//2
}
class AirLineCreator
method getWayPointMissionPath
public static PathResultMission getWayPointMissionPath(PathMission mission)
Description: Calls the algorithm to convert the configured waypoint flight attributes to a specific route plan.
Input parameter: PathMission. Manually configured waypoint flight attributes
Output parameter: PathResultMission Route planning result
**Related parameter: PathMission
method writeMissionFile
public static boolean writeMissionFile(String path, TaskModel taskModel)
Description: Writes the route planning result into a local file.
Input parameter: path. Path of the local location
Input parameter: TaskModel. Route planning entity class generated by the algorithm
Output parameter bool. true: write successful false: write failed
class PathResultMission
Description: The route planning algorithm outputs the result.
public class PathResultMission {
/** Total flight time */
public float T_ttl_fly;
/** Total flight distance */
public float L_ttl_fly;
/** Total number of photos */
public int Photo_Num;
/** Area, N/A for waypoint missions */
public double area;
/** Number of routes */
public short FPNum;
/** Number of plotting points */
public int Pts4PlotNum;
/** Expand the coordinates of all plotting points (Pts4PlotNum longitudes, Pts4PlotNum latitudes, Pts4PlotNum altitudes, the rest is 0; Valid value = The first 3 * Pts4PlotNum */
public double[] Pts4PlotLLA;//141030
/** Number of arrows **/
public int ArrowNum;
/** Arrow latitude, longitude, altitude, height, and direction (east: x-axis; south: y-axis; downward: z-axis) Expand the coordinates of all arrow points (ArrowNum latitudes, ArrowNum longitudes, ArrowNum altitudes, ArrowNum arrow directions; Valid value = The first 4 * ArrowNum **/
public double[] ArrowPosDirLLA;
/** Maximum radius that can be set at the waypoint **/
public float[] R_max;
/* The number of valid points for the route information is FPNum. */
public PathResultLine[] FP_Info_strc;
}
class MissionManager
method startMission
void startMission(CallbackWithNoParam startCallback);
Description: Makes the aircraft start a mission.
Input parameter: None
Output parameter: None
**Related parameter: CallbackWithNoParam
method pauseMission
void pauseMission(CallbackWithNoParam startCallback);
Description: Pauses the mission being performed by the aircraft.
Input parameter: None
Output parameter: None
**Related parameter: CallbackWithNoParam
method resumeMission
void resumeMission(CallbackWithNoParam startCallback);
Description: Resumes the mission suspended by the aircraft.
Input parameter: None
Output parameter: None
**Related parameter: CallbackWithNoParam
method cancelMission
void cancelMission(CallbackWithNoParam startCallback);
Description: Cancels the mission being performed by the aircraft.
Input parameter: None
Output parameter: None
**Related parameter: CallbackWithNoParam
class CallbackWithNoParam
method onSuccess
void onSuccess()
Description: Callback of success.
Input parameter: None
Output parameter: None
method onSuccess
void onFailure(AutelError error)
Description: Callback of failure.
Input parameter: None
Output parameter: None