Plane Commands in Guided Mode¶
This article lists the MAVLink commands that affect the movement of a Plane or QuadPlane. Normally these commands are sent by a ground station or Companion Computers often running DroneKit.
Note
The code which processes these commands can be found here in GCS_Mavlink.cpp
Movement commands¶
To command a plane to move to a particular lat, lon, alt send a MAV_CMD_NAV_WAYPOINT (16) within a MISSION_ITEM_INT with the following fields set as follows:
“current” = 2 to indicate that it is a guided mode “goto” message
“frame” = 0 or 3 for alt-above-sea-level, 6 for alt-above-home or 11 for alt-above-terrain
“x” = longitude * 1e7
“y” = latitude * 1e7
“z” = altitude in meters
Examples
Here are some example commands that can be copy-pasted into MAVProxy (aka SITL) to test this command. Before running these commands:
module load message
create an Auto mission (“wp editor”) with a NAV_TAKEOFF command with Alt of 100m
arm throttle
Auto (wait until vehicle begins circling)
GUIDED (and enter one of the commands below)
Example MAVProxy/SITL Command |
Description |
---|---|
|
fly to lat,lon of -35.36,149.16 and 700m above sea level |
|
fly to lat,lon of -35.36,149.16 and 100m above home |
|
fly to lat,lon of -35.36,149.16 and 100m above terrain |
MAV_CMDs¶
These MAV_CMDs can be processed if packaged within a COMMAND_LONG message
These MAV_CMDs can be processed if packaged within a COMMAND_INT message
Position Targets¶
To command the altitude in any supported frame, use SET_POSITION_TARGET_GLOBAL_INT. Ensure to set the POSITION_TARGET_TYPEMASK bit 3.
To command the altitude in LOCAL frame, use SET_POSITION_TARGET_LOCAL_NED.
It is currently not necessary to bother with POSITION_TARGET_TYPEMASK.
The MAV_FRAME must be MAV_FRAME_LOCAL_OFFSET_NED
.
No other fields in position target messages are currently supported. Use Movement commands to send a lat lon alt target.
Attitude Targets¶
The low level attitude of the vehicle can be controlled with SET_ATTITUDE_TARGET.