Copter Commands in Guided Mode

This article lists the commands that are handled by Copter in GUIDED mode (for example, when writing GCS or Companion Computer apps in DroneKit). Except where explicitly stated, most of these can also be called in other modes too.

Note

The list is inferred from Copter’s GCS_Mavlink.cpp for AC3.3.

Movement commands

These commands can only be called in GUIDED Mode. They are used for position and velocity control of the vehicle.

SET_POSITION_TARGET_LOCAL_NED

SET_POSITION_TARGET_GLOBAL_INT

MAV_CMDs

These MAV_CMDs can be processed if packaged within a COMMAND_LONG message.

MAV_CMD_NAV_TAKEOFF (Copter 3.2.1 or earlier)

MAV_CMD_NAV_LOITER_UNLIM (Copter 3.2.1 or earlier)

MAV_CMD_NAV_RETURN_TO_LAUNCH (Copter 3.2.1 or earlier)

MAV_CMD_NAV_LAND (Copter 3.2.1 or earlier)

MAV_CMD_CONDITION_YAW (Copter 3.2.1 or earlier)

MAV_CMD_DO_CHANGE_SPEED (Copter 3.2.1 or earlier)

MAV_CMD_DO_SET_HOME (Copter 3.2.1 or earlier)

MAV_CMD_DO_SET_ROI (Copter 3.2.1 or earlier)

MAV_CMD_MISSION_START (Copter 3.2.1 or earlier)

MAV_CMD_COMPONENT_ARM_DISARM (Copter 3.2.1 or earlier)

MAV_CMD_DO_SET_SERVO (Copter 3.2.1 or earlier)

MAV_CMD_DO_REPEAT_SERVO (Copter 3.2.1 or earlier)

MAV_CMD_DO_SET_RELAY (Copter 3.2.1 or earlier)

MAV_CMD_DO_REPEAT_RELAY (Copter 3.2.1 or earlier)

MAV_CMD_DO_FENCE_ENABLE (Copter 3.2.1 or earlier)

MAV_CMD_DO_PARACHUTE (If parachute enabled) (Copter 3.2.1 or earlier)

MAV_CMD_DO_GRIPPER (If gripper enabled) (Copter 3.2.1 or earlier)

MAV_CMD_START_RX_PAIR (Copter 3.3) Starts receiver pairing

MAV_CMD_PREFLIGHT_CALIBRATION (Copter 3.3)

MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS (Copter 3.3)

MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN (Copter 3.3)

MAV_CMD_DO_MOTOR_TEST (Copter 3.3)

MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES (Copter 3.3)

MAV_CMD_GET_HOME_POSITION (Copter 3.3)

MAV_CMD_DO_START_MAG_CAL (Master - not in Copter 3.3)

MAV_CMD_DO_ACCEPT_MAG_CAL (Master - not in Copter 3.3)

MAV_CMD_DO_CANCEL_MAG_CAL (Master - not in Copter 3.3)

MAV_CMD_DO_FLIGHTTERMINATION (Copter 3.3) Disarms motors immediately (Copter falls!).

MAV_CMD_DO_SEND_BANNER - No link available (?)

These MAV_CMD commands can be sent as their own message type (not inside :ref:`COMMAND_LONG`): MAV_CMD_DO_DIGICAM_CONFIGURE <copter:mav_cmd_do_digicam_configure>

MAV_CMD_DO_DIGICAM_CONTROL

MAV_CMD_DO_MOUNT_CONFIGURE

MAV_CMD_DO_MOUNT_CONTROL

Command definitions

This section contains information about some immediate commands supported by Copter (Mission Commands are documented in MAVLink Mission Command Messages (MAV_CMD)).

Note

Editors: It may make sense to merge the immediate command information for Copter/Plane/Rover as done for Mission Commands when we have a few more

SET_POSITION_TARGET_LOCAL_NED

Set vehicle position or velocity setpoint in local frame.

Note

Starting in Copter 3.3, velocity commands should be resent every second (the vehicle will stop after a few seconds if no command is received). Prior to Copter 3.3 the command was persistent, and would only be interrupted when the next movement command was received.

Command parameters

Command Field Description
time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
target_system System ID
target_component Component ID
coordinate_frame Valid options are listed below
type_mask

Bitmask to indicate which dimensions should be ignored by the vehicle (a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored). Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9:

Note

At time of writing you must enable all three bits for the position (0b0000111111111000) OR all three bits for the velocity (0b0000111111000111). Setting just one bit of the position/velocity or mixing the bits is not supported. The acceleration, yaw, yaw_rate are present in the protocol definition but are not supported by ArduPilot.

x X Position in specified NED frame in meters
y y Position in specified NED frame in meters
z Z Position in specified NED frame in meters (note, altitude is negative in NED)
vx X velocity in specified NED frame in meter/s
vy Y velocity in NED frame in meter/s
vz Z velocity in NED frame in meter/s
afx X acceleration or force (if bit 10 of type_mask is set) in specified NED frame in meter/s^2 or N
afy Y acceleration or force (if bit 10 of type_mask is set) in specified NED frame in meter/s^2 or N
afz Z acceleration or force (if bit 10 of type_mask is set) in specified NED frame in meter/s^2 or N
yaw yaw setpoint in rad
yaw_rate yaw rate setpoint in rad/s

Note

The co-ordinate frame information below applies from AC3.3. Prior to AC3.3, the field is ignored and all values are relative to the MAV_FRAME_LOCAL_NED frame.

The co-ordinate frame field takes the following values:

Frame Description
MAV_FRAME_LOCAL_NED

Positions are relative to the vehicle’s home position in the North, East, Down (NED) frame. Use this to specify a position x metres north, y metres east and (-) z metres above the home position.

Velocity directions are in the North, East, Down (NED) frame.

MAV_FRAME_LOCAL_OFFSET_NED

Positions are relative to the current vehicle position in the North, East, Down (NED) frame. Use this to specify a position x metres north, y metres east and (-) z metres of the current vehicle position.

Velocity directions are in the North, East, Down (NED) frame.

MAV_FRAME_BODY_OFFSET_NED

Positions are relative to the current vehicle position in a frame based on the vehicle’s current heading. Use this to specify a position x metres forward from the current vehicle position, y metres to the right, and z metres down (forward, right and down are “positive” values).

Velocity directions are relative to the current vehicle heading. Use this to specify the speed forward, right and down (or the opposite if you use negative values).

MAV_FRAME_BODY_NED

Positions are relative to the vehicle’s home position in the North, East, Down (NED) frame. Use this to specify a position x metres north, y metres east and (-) z metres above the home position.

Velocity directions are relative to the current vehicle heading. Use this to specify the speed forward, right and down (or the opposite if you use negative values).

Tip

In frames, _OFFSET_ means “relative to vehicle position” while _LOCAL_ is “relative to home position” (these have no impact on velocity directions). _BODY_ means that velocity components are relative to the heading of the vehicle rather than the NED frame.

SET_POSITION_TARGET_GLOBAL_INT

Set vehicle position, velocity and acceleration setpoint in the WGS84 coordinate system.

Note

Starting in Copter 3.3, velocity commands should be resent every second (the vehicle will stop after a few seconds if no command is received). Prior to Copter 3.3 the command was persistent, and would only be interrupted when the next movement command was received.

The protocol definition is here: SET_POSITION_TARGET_GLOBAL_INT.

Command parameters

Command Field Description
time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
target_system System ID
target_component Component ID
coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT
type_mask

Bitmask to indicate which dimensions should be ignored by the vehicle (a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored). Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9:

Note

At time of writing you must enable all three bits for the position (0b0000111111111000) OR all three bits for the velocity (0b0000111111000111). Setting just one bit of the position/velocity or mixing the bits is not supported. The acceleration, yaw, yaw_rate are present in the protocol definition but are not supported by ArduPilot.

lat_int X Position in WGS84 frame in 1e7 \* meters
lon_int Y Position in WGS84 frame in 1e7 \* meters
alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
vx X velocity in MAV_FRAME_LOCAL_NED frame in meter/s
vy Y velocity in MAV_FRAME_LOCAL_NED frame in meter/s
vz Z velocity in MAV_FRAME_LOCAL_NED frame in meter/s
afx X acceleration or force (if bit 10 of type_mask is set) in specified MAV_FRAME_LOCAL_NED frame in meter/s^2 or N
afy Y acceleration or force (if bit 10 of type_mask is set) in specified MAV_FRAME_LOCAL_NED frame in meter/s^2 or N
afz Z acceleration or force (if bit 10 of type_mask is set) in specified MAV_FRAME_LOCAL_NED frame in meter/s^2 or N
yaw yaw setpoint in rad
yaw_rate yaw rate setpoint in rad/s

SET_HOME_POSITION

The position the system will return to and land on. The position is set automatically by the system during the takeoff if it has not been explicitly set by the operator before or after.

Note

Not in Copter 3.3 (currently in master)

Command parameters

Command Field Type Description
target_system uint8_t System ID
latitude int32_t Latitude (WGS84), in degrees \* 1E7
longitude int32_t Longitude (WGS84), in degrees \* 1E7
altitude int32_t Altitude (AMSL), in meters \* 1000 (positive for up)
x float Local X position of this position in the local coordinate frame.
y float Local Y position of this position in the local coordinate frame
z float Local Z position of this position in the local coordinate frame
q float[4] World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground.
approach_x float Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_y float Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_z float Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.

The protocol definition for this command is here: SET_HOME_POSITION