mavlink

package
v0.0.0-...-10d700b Latest Latest
Warning

This package is not in the latest version of its module.

Go to latest
Published: Dec 14, 2015 License: Apache-2.0 Imports: 7 Imported by: 1

Documentation

Overview

Package mavlink provides support for encoding/decoding mavlink (http://qgroundcontrol.org/mavlink/start) messages.

Encoding is done via the Encoder type, which wraps an io.Writer, and decoding is done via the Decoder type, which wraps an io.Reader.

The Packet type represents the wire type used for message transmission/reception, and a variety of generated classes each implement the Message type. A Message can be converted to a Packet by calling Message.Pack(p) and a Packet can be converted to a Message by calling Message.Unpack(p).

See the ReadMe for examples of typical usage.

Index

Constants

View Source
const (
	MAV_CMD_DO_MOTOR_TEST      = 209 // Mission command to perform motor test
	MAV_CMD_DO_GRIPPER         = 211 // Mission command to operate EPM gripper
	MAV_CMD_DO_AUTOTUNE_ENABLE = 212 // Enable/disable autotune
	MAV_CMD_NAV_ALTITUDE_WAIT  = 83  // Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up.
	MAV_CMD_DO_START_MAG_CAL   = 4   // Initiate a magnetometer calibration
	MAV_CMD_DO_ACCEPT_MAG_CAL  = 5   // Initiate a magnetometer calibration
	MAV_CMD_DO_CANCEL_MAG_CAL  = 6   // Cancel a running magnetometer calibration
)

MavCmd:

View Source
const (
	LIMITS_INIT       = 0 //  pre-initialization
	LIMITS_DISABLED   = 1 //  disabled
	LIMITS_ENABLED    = 2 //  checking limits
	LIMITS_TRIGGERED  = 3 //  a limit has been breached
	LIMITS_RECOVERING = 4 //  taking action eg. RTL
	LIMITS_RECOVERED  = 5 //  we're no longer in breach of a limit
)

LimitsState:

View Source
const (
	LIMIT_GPSLOCK  = 1 //  pre-initialization
	LIMIT_GEOFENCE = 2 //  disabled
	LIMIT_ALTITUDE = 4 //  checking limits
)

LimitModule:

View Source
const (
	FAVORABLE_WIND   = 1 // Flag set when requiring favorable winds for landing.
	LAND_IMMEDIATELY = 2 // Flag set when plane is to immediately descend to break altitude and land without GCS intervention.  Flag not set when plane is to loiter at Rally point until commanded to land.
)

RallyFlags: Flags in RALLY_POINT message

View Source
const (
	PARACHUTE_DISABLE = 0 // Disable parachute release
	PARACHUTE_ENABLE  = 1 // Enable parachute release
	PARACHUTE_RELEASE = 2 // Release parachute
)

ParachuteAction:

View Source
const (
	MOTOR_TEST_THROTTLE_PERCENT = 0 // throttle as a percentage from 0 ~ 100
	MOTOR_TEST_THROTTLE_PWM     = 1 // throttle as an absolute PWM value (normally in range of 1000~2000)
	MOTOR_TEST_THROTTLE_PILOT   = 2 // throttle pass-through from pilot's transmitter
)

MotorTestThrottleType:

View Source
const (
	GRIPPER_ACTION_RELEASE = 0 // gripper release of cargo
	GRIPPER_ACTION_GRAB    = 1 // gripper grabs onto cargo
)

GripperActions: Gripper actions.

View Source
const (
	CAMERA_STATUS_TYPE_HEARTBEAT  = 0 // Camera heartbeat, announce camera component ID at 1hz
	CAMERA_STATUS_TYPE_TRIGGER    = 1 // Camera image triggered
	CAMERA_STATUS_TYPE_DISCONNECT = 2 // Camera connection lost
	CAMERA_STATUS_TYPE_ERROR      = 3 // Camera unknown error
	CAMERA_STATUS_TYPE_LOWBATT    = 4 // Camera battery low. Parameter p1 shows reported voltage
	CAMERA_STATUS_TYPE_LOWSTORE   = 5 // Camera storage low. Parameter p1 shows reported shots remaining
	CAMERA_STATUS_TYPE_LOWSTOREV  = 6 // Camera storage low. Parameter p1 shows reported video minutes remaining
)

CameraStatusTypes:

View Source
const (
	CAMERA_FEEDBACK_PHOTO       = 0 // Shooting photos, not video
	CAMERA_FEEDBACK_VIDEO       = 1 // Shooting video, not stills
	CAMERA_FEEDBACK_BADEXPOSURE = 2 // Unable to achieve requested exposure (e.g. shutter speed too low)
	CAMERA_FEEDBACK_CLOSEDLOOP  = 3 // Closed loop feedback from camera, we know for sure it has successfully taken a picture
	CAMERA_FEEDBACK_OPENLOOP    = 4 // Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture
)

CameraFeedbackFlags:

View Source
const (
	MAV_MODE_GIMBAL_UNINITIALIZED     = 0 // Gimbal is powered on but has not started initializing yet
	MAV_MODE_GIMBAL_CALIBRATING_PITCH = 1 // Gimbal is currently running calibration on the pitch axis
	MAV_MODE_GIMBAL_CALIBRATING_ROLL  = 2 // Gimbal is currently running calibration on the roll axis
	MAV_MODE_GIMBAL_CALIBRATING_YAW   = 3 // Gimbal is currently running calibration on the yaw axis
	MAV_MODE_GIMBAL_INITIALIZED       = 4 // Gimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter
	MAV_MODE_GIMBAL_ACTIVE            = 5 // Gimbal is actively stabilizing
	MAV_MODE_GIMBAL_RATE_CMD_TIMEOUT  = 6 // Gimbal is relaxed because it missed more than 10 expected rate command messages in a row.  Gimbal will move back to active mode when it receives a new rate command
)

MavModeGimbal:

View Source
const (
	GIMBAL_AXIS_YAW   = 0 // Gimbal yaw axis
	GIMBAL_AXIS_PITCH = 1 // Gimbal pitch axis
	GIMBAL_AXIS_ROLL  = 2 // Gimbal roll axis
)

GimbalAxis:

View Source
const (
	GIMBAL_AXIS_CALIBRATION_STATUS_IN_PROGRESS = 0 // Axis calibration is in progress
	GIMBAL_AXIS_CALIBRATION_STATUS_SUCCEEDED   = 1 // Axis calibration succeeded
	GIMBAL_AXIS_CALIBRATION_STATUS_FAILED      = 2 // Axis calibration failed
)

GimbalAxisCalibrationStatus:

View Source
const (
	GOPRO_CMD_RESULT_UNKNOWN                        = 0  // The result of the command is unknown
	GOPRO_CMD_RESULT_SUCCESSFUL                     = 1  // The command was successfully sent, and a response was successfully received
	GOPRO_CMD_RESULT_SEND_CMD_START_TIMEOUT         = 2  // Timed out waiting for the GoPro to acknowledge our request to send a command
	GOPRO_CMD_RESULT_SEND_CMD_COMPLETE_TIMEOUT      = 3  // Timed out waiting for the GoPro to read the command
	GOPRO_CMD_RESULT_GET_RESPONSE_START_TIMEOUT     = 4  // Timed out waiting for the GoPro to begin transmitting a response to the command
	GOPRO_CMD_RESULT_GET_RESPONSE_COMPLETE_TIMEOUT  = 5  // Timed out waiting for the GoPro to finish transmitting a response to the command
	GOPRO_CMD_RESULT_GET_CMD_COMPLETE_TIMEOUT       = 6  // Timed out waiting for the GoPro to finish transmitting its own command
	GOPRO_CMD_RESULT_SEND_RESPONSE_START_TIMEOUT    = 7  // Timed out waiting for the GoPro to start reading a response to its own command
	GOPRO_CMD_RESULT_SEND_RESPONSE_COMPLETE_TIMEOUT = 8  // Timed out waiting for the GoPro to finish reading a response to its own command
	GOPRO_CMD_RESULT_PREEMPTED                      = 9  // Command to the GoPro was preempted by the GoPro sending its own command
	GOPRO_CMD_RECEIVED_DATA_OVERFLOW                = 10 // More data than expected received in response to the command
	GOPRO_CMD_RECEIVED_DATA_UNDERFLOW               = 11 // Less data than expected received in response to the command
)

GoproCmdResult:

View Source
const (
	LED_CONTROL_PATTERN_OFF            = 0   // LED patterns off (return control to regular vehicle control)
	LED_CONTROL_PATTERN_FIRMWAREUPDATE = 1   // LEDs show pattern during firmware update
	LED_CONTROL_PATTERN_CUSTOM         = 255 // Custom Pattern using custom bytes fields
)

LedControlPattern:

View Source
const (
	EKF_ATTITUDE           = 1   // set if EKF's attitude estimate is good
	EKF_VELOCITY_HORIZ     = 2   // set if EKF's horizontal velocity estimate is good
	EKF_VELOCITY_VERT      = 4   // set if EKF's vertical velocity estimate is good
	EKF_POS_HORIZ_REL      = 8   // set if EKF's horizontal position (relative) estimate is good
	EKF_POS_HORIZ_ABS      = 16  // set if EKF's horizontal position (absolute) estimate is good
	EKF_POS_VERT_ABS       = 32  // set if EKF's vertical position (absolute) estimate is good
	EKF_POS_VERT_AGL       = 64  // set if EKF's vertical position (above ground) estimate is good
	EKF_CONST_POS_MODE     = 128 // EKF is in constant position mode and does not know it's absolute or relative position
	EKF_PRED_POS_HORIZ_REL = 8   // set if EKF's predicted horizontal position (relative) estimate is good
	EKF_PRED_POS_HORIZ_ABS = 9   // set if EKF's predicted horizontal position (absolute) estimate is good
)

EkfStatusFlags: Flags in EKF_STATUS message

View Source
const (
	MAG_CAL_NOT_STARTED      = 0 //
	MAG_CAL_WAITING_TO_START = 1 //
	MAG_CAL_RUNNING_STEP_ONE = 2 //
	MAG_CAL_RUNNING_STEP_TWO = 3 //
	MAG_CAL_SUCCESS          = 4 //
	MAG_CAL_FAILED           = 5 //
)

MagCalStatus:

View Source
const (
	PID_TUNING_ROLL  = 1 //
	PID_TUNING_PITCH = 2 //
	PID_TUNING_YAW   = 3 //
	PID_TUNING_ACCZ  = 4 //
	PID_TUNING_STEER = 5 //
)

PidTuningAxis:

View Source
const (
	MSG_ID_SENSOR_OFFSETS                        = 150
	MSG_ID_SET_MAG_OFFSETS                       = 151
	MSG_ID_MEMINFO                               = 152
	MSG_ID_AP_ADC                                = 153
	MSG_ID_DIGICAM_CONFIGURE                     = 154
	MSG_ID_DIGICAM_CONTROL                       = 155
	MSG_ID_MOUNT_CONFIGURE                       = 156
	MSG_ID_MOUNT_CONTROL                         = 157
	MSG_ID_MOUNT_STATUS                          = 158
	MSG_ID_FENCE_POINT                           = 160
	MSG_ID_FENCE_FETCH_POINT                     = 161
	MSG_ID_FENCE_STATUS                          = 162
	MSG_ID_AHRS                                  = 163
	MSG_ID_SIMSTATE                              = 164
	MSG_ID_HWSTATUS                              = 165
	MSG_ID_RADIO                                 = 166
	MSG_ID_LIMITS_STATUS                         = 167
	MSG_ID_WIND                                  = 168
	MSG_ID_DATA16                                = 169
	MSG_ID_DATA32                                = 170
	MSG_ID_DATA64                                = 171
	MSG_ID_DATA96                                = 172
	MSG_ID_RANGEFINDER                           = 173
	MSG_ID_AIRSPEED_AUTOCAL                      = 174
	MSG_ID_RALLY_POINT                           = 175
	MSG_ID_RALLY_FETCH_POINT                     = 176
	MSG_ID_COMPASSMOT_STATUS                     = 177
	MSG_ID_AHRS2                                 = 178
	MSG_ID_CAMERA_STATUS                         = 179
	MSG_ID_CAMERA_FEEDBACK                       = 180
	MSG_ID_BATTERY2                              = 181
	MSG_ID_AHRS3                                 = 182
	MSG_ID_AUTOPILOT_VERSION_REQUEST             = 183
	MSG_ID_LED_CONTROL                           = 186
	MSG_ID_MAG_CAL_PROGRESS                      = 191
	MSG_ID_MAG_CAL_REPORT                        = 192
	MSG_ID_EKF_STATUS_REPORT                     = 193
	MSG_ID_PID_TUNING                            = 194
	MSG_ID_GIMBAL_REPORT                         = 200
	MSG_ID_GIMBAL_CONTROL                        = 201
	MSG_ID_GIMBAL_RESET                          = 202
	MSG_ID_GIMBAL_AXIS_CALIBRATION_PROGRESS      = 203
	MSG_ID_GIMBAL_SET_HOME_OFFSETS               = 204
	MSG_ID_GIMBAL_HOME_OFFSET_CALIBRATION_RESULT = 205
	MSG_ID_GIMBAL_SET_FACTORY_PARAMETERS         = 206
	MSG_ID_GIMBAL_FACTORY_PARAMETERS_LOADED      = 207
	MSG_ID_GIMBAL_ERASE_FIRMWARE_AND_CONFIG      = 208
	MSG_ID_GIMBAL_PERFORM_FACTORY_TESTS          = 209
	MSG_ID_GIMBAL_REPORT_FACTORY_TESTS_PROGRESS  = 210
	MSG_ID_GOPRO_POWER_ON                        = 215
	MSG_ID_GOPRO_POWER_OFF                       = 216
	MSG_ID_GOPRO_COMMAND                         = 217
	MSG_ID_GOPRO_RESPONSE                        = 218
	MSG_ID_RPM                                   = 226
)

Message IDs

View Source
const (
	MAV_CMD_RESET_MPPT      = 0 // Mission command to reset Maximum Power Point Tracker (MPPT)
	MAV_CMD_PAYLOAD_CONTROL = 1 // Mission command to perform a power cycle on payload
)

MavCmd:

View Source
const (
	MSG_ID_SENS_POWER       = 201
	MSG_ID_SENS_MPPT        = 202
	MSG_ID_ASLCTRL_DATA     = 203
	MSG_ID_ASLCTRL_DEBUG    = 204
	MSG_ID_ASLUAV_STATUS    = 205
	MSG_ID_EKF_EXT          = 206
	MSG_ID_ASL_OBCTRL       = 207
	MSG_ID_SENS_ATMOS       = 208
	MSG_ID_SENS_BATMON      = 209
	MSG_ID_FW_SOARING_DATA  = 210
	MSG_ID_SENSORPOD_STATUS = 211
)

Message IDs

View Source
const (
	MAV_AUTOPILOT_GENERIC                                      = 0  // Generic autopilot, full support for everything
	MAV_AUTOPILOT_RESERVED                                     = 1  // Reserved for future use.
	MAV_AUTOPILOT_SLUGS                                        = 2  // SLUGS autopilot, http://slugsuav.soe.ucsc.edu
	MAV_AUTOPILOT_ARDUPILOTMEGA                                = 3  // ArduPilotMega / ArduCopter, http://diydrones.com
	MAV_AUTOPILOT_OPENPILOT                                    = 4  // OpenPilot, http://openpilot.org
	MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY                       = 5  // Generic autopilot only supporting simple waypoints
	MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6  // Generic autopilot supporting waypoints and other simple navigation commands
	MAV_AUTOPILOT_GENERIC_MISSION_FULL                         = 7  // Generic autopilot supporting the full mission command set
	MAV_AUTOPILOT_INVALID                                      = 8  // No valid autopilot, e.g. a GCS or other MAVLink component
	MAV_AUTOPILOT_PPZ                                          = 9  // PPZ UAV - http://nongnu.org/paparazzi
	MAV_AUTOPILOT_UDB                                          = 10 // UAV Dev Board
	MAV_AUTOPILOT_FP                                           = 11 // FlexiPilot
	MAV_AUTOPILOT_PX4                                          = 12 // PX4 Autopilot - http://pixhawk.ethz.ch/px4/
	MAV_AUTOPILOT_SMACCMPILOT                                  = 13 // SMACCMPilot - http://smaccmpilot.org
	MAV_AUTOPILOT_AUTOQUAD                                     = 14 // AutoQuad -- http://autoquad.org
	MAV_AUTOPILOT_ARMAZILA                                     = 15 // Armazila -- http://armazila.com
	MAV_AUTOPILOT_AEROB                                        = 16 // Aerob -- http://aerob.ru
	MAV_AUTOPILOT_ASLUAV                                       = 17 // ASLUAV autopilot -- http://www.asl.ethz.ch
)

MavAutopilot: Micro air vehicle / autopilot classes. This identifies the individual model.

View Source
const (
	MAV_TYPE_GENERIC            = 0  // Generic micro air vehicle.
	MAV_TYPE_FIXED_WING         = 1  // Fixed wing aircraft.
	MAV_TYPE_QUADROTOR          = 2  // Quadrotor
	MAV_TYPE_COAXIAL            = 3  // Coaxial helicopter
	MAV_TYPE_HELICOPTER         = 4  // Normal helicopter with tail rotor.
	MAV_TYPE_ANTENNA_TRACKER    = 5  // Ground installation
	MAV_TYPE_GCS                = 6  // Operator control unit / ground control station
	MAV_TYPE_AIRSHIP            = 7  // Airship, controlled
	MAV_TYPE_FREE_BALLOON       = 8  // Free balloon, uncontrolled
	MAV_TYPE_ROCKET             = 9  // Rocket
	MAV_TYPE_GROUND_ROVER       = 10 // Ground rover
	MAV_TYPE_SURFACE_BOAT       = 11 // Surface vessel, boat, ship
	MAV_TYPE_SUBMARINE          = 12 // Submarine
	MAV_TYPE_HEXAROTOR          = 13 // Hexarotor
	MAV_TYPE_OCTOROTOR          = 14 // Octorotor
	MAV_TYPE_TRICOPTER          = 15 // Octorotor
	MAV_TYPE_FLAPPING_WING      = 16 // Flapping wing
	MAV_TYPE_KITE               = 17 // Flapping wing
	MAV_TYPE_ONBOARD_CONTROLLER = 18 // Onboard companion controller
	MAV_TYPE_VTOL_DUOROTOR      = 19 // Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.
	MAV_TYPE_VTOL_QUADROTOR     = 20 // Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.
	MAV_TYPE_VTOL_TILTROTOR     = 21 // Tiltrotor VTOL
	MAV_TYPE_VTOL_RESERVED2     = 22 // VTOL reserved 2
	MAV_TYPE_VTOL_RESERVED3     = 23 // VTOL reserved 3
	MAV_TYPE_VTOL_RESERVED4     = 24 // VTOL reserved 4
	MAV_TYPE_VTOL_RESERVED5     = 25 // VTOL reserved 5
	MAV_TYPE_GIMBAL             = 26 // Onboard gimbal
	MAV_TYPE_ADSB               = 27 // Onboard ADSB peripheral
)

MavType:

View Source
const (
	FIRMWARE_VERSION_TYPE_DEV      = 0   // development release
	FIRMWARE_VERSION_TYPE_ALPHA    = 64  // alpha release
	FIRMWARE_VERSION_TYPE_BETA     = 128 // beta release
	FIRMWARE_VERSION_TYPE_RC       = 192 // release candidate
	FIRMWARE_VERSION_TYPE_OFFICIAL = 255 // official stable release
)

FirmwareVersionType: These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65.

View Source
const (
	MAV_MODE_FLAG_SAFETY_ARMED         = 128 // 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly.
	MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64  // 0b01000000 remote control input is enabled.
	MAV_MODE_FLAG_HIL_ENABLED          = 32  // 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational.
	MAV_MODE_FLAG_STABILIZE_ENABLED    = 16  // 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.
	MAV_MODE_FLAG_GUIDED_ENABLED       = 8   // 0b00001000 guided mode enabled, system flies MISSIONs / mission items.
	MAV_MODE_FLAG_AUTO_ENABLED         = 4   // 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.
	MAV_MODE_FLAG_TEST_ENABLED         = 2   // 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.
	MAV_MODE_FLAG_CUSTOM_MODE_ENABLED  = 1   // 0b00000001 Reserved for future use.
)

MavModeFlag: These flags encode the MAV mode.

View Source
const (
	MAV_MODE_FLAG_DECODE_POSITION_SAFETY      = 128 // First bit:  10000000
	MAV_MODE_FLAG_DECODE_POSITION_MANUAL      = 64  // Second bit: 01000000
	MAV_MODE_FLAG_DECODE_POSITION_HIL         = 32  // Third bit:  00100000
	MAV_MODE_FLAG_DECODE_POSITION_STABILIZE   = 16  // Fourth bit: 00010000
	MAV_MODE_FLAG_DECODE_POSITION_GUIDED      = 8   // Fifth bit:  00001000
	MAV_MODE_FLAG_DECODE_POSITION_AUTO        = 4   // Sixt bit:   00000100
	MAV_MODE_FLAG_DECODE_POSITION_TEST        = 2   // Seventh bit: 00000010
	MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1   // Eighth bit: 00000001
)

MavModeFlagDecodePosition: These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not.

View Source
const (
	MAV_GOTO_DO_HOLD                    = 0 // Hold at the current position.
	MAV_GOTO_DO_CONTINUE                = 1 // Continue with the next item in mission execution.
	MAV_GOTO_HOLD_AT_CURRENT_POSITION   = 2 // Hold at the current position of the system
	MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3 // Hold at the position specified in the parameters of the DO_HOLD action
)

MavGoto: Override command, pauses current mission execution and moves immediately to a position

View Source
const (
	MAV_MODE_PREFLIGHT          = 0   // System is not ready to fly, booting, calibrating, etc. No flag is set.
	MAV_MODE_STABILIZE_DISARMED = 80  // System is allowed to be active, under assisted RC control.
	MAV_MODE_STABILIZE_ARMED    = 208 // System is allowed to be active, under assisted RC control.
	MAV_MODE_MANUAL_DISARMED    = 64  // System is allowed to be active, under manual (RC) control, no stabilization
	MAV_MODE_MANUAL_ARMED       = 192 // System is allowed to be active, under manual (RC) control, no stabilization
	MAV_MODE_GUIDED_DISARMED    = 88  // System is allowed to be active, under autonomous control, manual setpoint
	MAV_MODE_GUIDED_ARMED       = 216 // System is allowed to be active, under autonomous control, manual setpoint
	MAV_MODE_AUTO_DISARMED      = 92  // System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)
	MAV_MODE_AUTO_ARMED         = 220 // System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)
	MAV_MODE_TEST_DISARMED      = 66  // UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.
	MAV_MODE_TEST_ARMED         = 194 // UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.
)

MavMode: These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override.

View Source
const (
	MAV_STATE_UNINIT      = 0 // Uninitialized system, state is unknown.
	MAV_STATE_BOOT        = 1 // System is booting up.
	MAV_STATE_CALIBRATING = 2 // System is calibrating and not flight-ready.
	MAV_STATE_STANDBY     = 3 // System is grounded and on standby. It can be launched any time.
	MAV_STATE_ACTIVE      = 4 // System is active and might be already airborne. Motors are engaged.
	MAV_STATE_CRITICAL    = 5 // System is in a non-normal flight mode. It can however still navigate.
	MAV_STATE_EMERGENCY   = 6 // System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.
	MAV_STATE_POWEROFF    = 7 // System just initialized its power-down sequence, will shut down now.
)

MavState:

View Source
const (
	MAV_COMP_ID_ALL            = 0   //
	MAV_COMP_ID_GPS            = 220 //
	MAV_COMP_ID_MISSIONPLANNER = 190 //
	MAV_COMP_ID_PATHPLANNER    = 195 //
	MAV_COMP_ID_MAPPER         = 180 //
	MAV_COMP_ID_CAMERA         = 100 //
	MAV_COMP_ID_IMU            = 200 //
	MAV_COMP_ID_IMU_2          = 201 //
	MAV_COMP_ID_IMU_3          = 202 //
	MAV_COMP_ID_UDP_BRIDGE     = 240 //
	MAV_COMP_ID_UART_BRIDGE    = 241 //
	MAV_COMP_ID_SYSTEM_CONTROL = 250 //
	MAV_COMP_ID_SERVO1         = 140 //
	MAV_COMP_ID_SERVO2         = 141 //
	MAV_COMP_ID_SERVO3         = 142 //
	MAV_COMP_ID_SERVO4         = 143 //
	MAV_COMP_ID_SERVO5         = 144 //
	MAV_COMP_ID_SERVO6         = 145 //
	MAV_COMP_ID_SERVO7         = 146 //
	MAV_COMP_ID_SERVO8         = 147 //
	MAV_COMP_ID_SERVO9         = 148 //
	MAV_COMP_ID_SERVO10        = 149 //
	MAV_COMP_ID_SERVO11        = 150 //
	MAV_COMP_ID_SERVO12        = 151 //
	MAV_COMP_ID_SERVO13        = 152 //
	MAV_COMP_ID_SERVO14        = 153 //
	MAV_COMP_ID_GIMBAL         = 154 //
	MAV_COMP_ID_ADSB           = 155 //
)

MavComponent:

View Source
const (
	MAV_SYS_STATUS_SENSOR_3D_GYRO                = 1   // 0x01 3D gyro
	MAV_SYS_STATUS_SENSOR_3D_ACCEL               = 2   // 0x02 3D accelerometer
	MAV_SYS_STATUS_SENSOR_3D_MAG                 = 4   // 0x04 3D magnetometer
	MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE      = 8   // 0x08 absolute pressure
	MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE  = 16  // 0x10 differential pressure
	MAV_SYS_STATUS_SENSOR_GPS                    = 32  // 0x20 GPS
	MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW           = 64  // 0x40 optical flow
	MAV_SYS_STATUS_SENSOR_VISION_POSITION        = 128 // 0x80 computer vision position
	MAV_SYS_STATUS_SENSOR_LASER_POSITION         = 8   // 0x100 laser based position
	MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH  = 9   // 0x200 external ground truth (Vicon or Leica)
	MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL   = 10  // 0x400 3D angular rate control
	MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 11  // 0x800 attitude stabilization
	MAV_SYS_STATUS_SENSOR_YAW_POSITION           = 12  // 0x1000 yaw position
	MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL     = 13  // 0x2000 z/altitude control
	MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL    = 14  // 0x4000 x/y position control
	MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS          = 15  // 0x8000 motor outputs / control
	MAV_SYS_STATUS_SENSOR_RC_RECEIVER            = 16  // 0x10000 rc receiver
	MAV_SYS_STATUS_SENSOR_3D_GYRO2               = 17  // 0x20000 2nd 3D gyro
	MAV_SYS_STATUS_SENSOR_3D_ACCEL2              = 18  // 0x40000 2nd 3D accelerometer
	MAV_SYS_STATUS_SENSOR_3D_MAG2                = 19  // 0x80000 2nd 3D magnetometer
	MAV_SYS_STATUS_GEOFENCE                      = 20  // 0x100000 geofence
	MAV_SYS_STATUS_AHRS                          = 21  // 0x200000 AHRS subsystem health
	MAV_SYS_STATUS_TERRAIN                       = 22  // 0x400000 Terrain subsystem health
)

MavSysStatusSensor: These encode the sensors whose status is sent as part of the SYS_STATUS message.

View Source
const (
	MAV_FRAME_GLOBAL                  = 0  // Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL)
	MAV_FRAME_LOCAL_NED               = 1  // Local coordinate frame, Z-up (x: north, y: east, z: down).
	MAV_FRAME_MISSION                 = 2  // NOT a coordinate frame, indicates a mission command.
	MAV_FRAME_GLOBAL_RELATIVE_ALT     = 3  // Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location.
	MAV_FRAME_LOCAL_ENU               = 4  // Local coordinate frame, Z-down (x: east, y: north, z: up)
	MAV_FRAME_GLOBAL_INT              = 5  // Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL)
	MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6  // Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location.
	MAV_FRAME_LOCAL_OFFSET_NED        = 7  // Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position.
	MAV_FRAME_BODY_NED                = 8  // Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right.
	MAV_FRAME_BODY_OFFSET_NED         = 9  // Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east.
	MAV_FRAME_GLOBAL_TERRAIN_ALT      = 10 // Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
	MAV_FRAME_GLOBAL_TERRAIN_ALT_INT  = 11 // Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
)

MavFrame:

View Source
const (
	MAVLINK_DATA_STREAM_IMG_JPEG   = 0 //
	MAVLINK_DATA_STREAM_IMG_BMP    = 1 //
	MAVLINK_DATA_STREAM_IMG_RAW8U  = 2 //
	MAVLINK_DATA_STREAM_IMG_RAW32U = 3 //
	MAVLINK_DATA_STREAM_IMG_PGM    = 4 //
	MAVLINK_DATA_STREAM_IMG_PNG    = 5 //
)

MavlinkDataStreamType:

View Source
const (
	FENCE_ACTION_NONE            = 0 // Disable fenced mode
	FENCE_ACTION_GUIDED          = 1 // Switched to guided mode to return point (fence point 0)
	FENCE_ACTION_REPORT          = 2 // Report fence breach, but don't take action
	FENCE_ACTION_GUIDED_THR_PASS = 3 // Switched to guided mode to return point (fence point 0) with manual throttle control
)

FenceAction:

View Source
const (
	FENCE_BREACH_NONE     = 0 // No last fence breach
	FENCE_BREACH_MINALT   = 1 // Breached minimum altitude
	FENCE_BREACH_MAXALT   = 2 // Breached maximum altitude
	FENCE_BREACH_BOUNDARY = 3 // Breached fence boundary
)

FenceBreach:

View Source
const (
	MAV_MOUNT_MODE_RETRACT           = 0 // Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization
	MAV_MOUNT_MODE_NEUTRAL           = 1 // Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory.
	MAV_MOUNT_MODE_MAVLINK_TARGETING = 2 // Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization
	MAV_MOUNT_MODE_RC_TARGETING      = 3 // Load neutral position and start RC Roll,Pitch,Yaw control with stabilization
	MAV_MOUNT_MODE_GPS_POINT         = 4 // Load neutral position and start to point to Lat,Lon,Alt
)

MavMountMode: Enumeration of possible mount operation modes

View Source
const (
	MAV_CMD_NAV_WAYPOINT                   = 16  // Navigate to MISSION.
	MAV_CMD_NAV_LOITER_UNLIM               = 17  // Loiter around this MISSION an unlimited amount of time
	MAV_CMD_NAV_LOITER_TURNS               = 18  // Loiter around this MISSION for X turns
	MAV_CMD_NAV_LOITER_TIME                = 19  // Loiter around this MISSION for X seconds
	MAV_CMD_NAV_RETURN_TO_LAUNCH           = 20  // Return to launch location
	MAV_CMD_NAV_LAND                       = 21  // Land at location
	MAV_CMD_NAV_TAKEOFF                    = 22  // Takeoff from ground / hand
	MAV_CMD_NAV_LAND_LOCAL                 = 23  // Land at local position (local frame only)
	MAV_CMD_NAV_TAKEOFF_LOCAL              = 24  // Takeoff from local position (local frame only)
	MAV_CMD_NAV_FOLLOW                     = 25  // Vehicle following, i.e. this waypoint represents the position of a moving vehicle
	MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT    = 30  // Continue on the current course and climb/descend to specified altitude.  When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached.
	MAV_CMD_NAV_LOITER_TO_ALT              = 31  // Begin loiter at the specified Latitude and Longitude.  If Lat=Lon=0, then loiter at the current position.  Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached.  Additionally, if the Heading Required parameter is non-zero the  aircraft will not leave the loiter until heading toward the next waypoint.
	MAV_CMD_NAV_ROI                        = 80  // Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.
	MAV_CMD_NAV_PATHPLANNING               = 81  // Control autonomous path planning on the MAV.
	MAV_CMD_NAV_SPLINE_WAYPOINT            = 82  // Navigate to MISSION using a spline path.
	MAV_CMD_NAV_GUIDED_ENABLE              = 92  // hand control over to an external controller
	MAV_CMD_NAV_LAST                       = 95  // NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration
	MAV_CMD_CONDITION_DELAY                = 112 // Delay mission state machine.
	MAV_CMD_CONDITION_CHANGE_ALT           = 113 // Ascend/descend at rate.  Delay mission state machine until desired altitude reached.
	MAV_CMD_CONDITION_DISTANCE             = 114 // Delay mission state machine until within desired distance of next NAV point.
	MAV_CMD_CONDITION_YAW                  = 115 // Reach a certain target angle.
	MAV_CMD_CONDITION_LAST                 = 159 // NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration
	MAV_CMD_DO_SET_MODE                    = 176 // Set system mode.
	MAV_CMD_DO_JUMP                        = 177 // Jump to the desired command in the mission list.  Repeat this action only the specified number of times
	MAV_CMD_DO_CHANGE_SPEED                = 178 // Change speed and/or throttle set points.
	MAV_CMD_DO_SET_HOME                    = 179 // Changes the home location either to the current location or a specified location.
	MAV_CMD_DO_SET_PARAMETER               = 180 // Set a system parameter.  Caution!  Use of this command requires knowledge of the numeric enumeration value of the parameter.
	MAV_CMD_DO_SET_RELAY                   = 181 // Set a relay to a condition.
	MAV_CMD_DO_REPEAT_RELAY                = 182 // Cycle a relay on and off for a desired number of cyles with a desired period.
	MAV_CMD_DO_SET_SERVO                   = 183 // Set a servo to a desired PWM value.
	MAV_CMD_DO_REPEAT_SERVO                = 184 // Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.
	MAV_CMD_DO_FLIGHTTERMINATION           = 185 // Terminate flight immediately
	MAV_CMD_DO_LAND_START                  = 189 // Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence.
	MAV_CMD_DO_RALLY_LAND                  = 190 // Mission command to perform a landing from a rally point.
	MAV_CMD_DO_GO_AROUND                   = 191 // Mission command to safely abort an autonmous landing.
	MAV_CMD_DO_CONTROL_VIDEO               = 200 // Control onboard camera system.
	MAV_CMD_DO_SET_ROI                     = 201 // Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.
	MAV_CMD_DO_DIGICAM_CONFIGURE           = 202 // Mission command to configure an on-board camera controller system.
	MAV_CMD_DO_DIGICAM_CONTROL             = 203 // Mission command to control an on-board camera controller system.
	MAV_CMD_DO_MOUNT_CONFIGURE             = 204 // Mission command to configure a camera or antenna mount
	MAV_CMD_DO_MOUNT_CONTROL               = 205 // Mission command to control a camera or antenna mount
	MAV_CMD_DO_SET_CAM_TRIGG_DIST          = 206 // Mission command to set CAM_TRIGG_DIST for this flight
	MAV_CMD_DO_FENCE_ENABLE                = 207 // Mission command to enable the geofence
	MAV_CMD_DO_PARACHUTE                   = 208 // Mission command to trigger a parachute
	MAV_CMD_DO_INVERTED_FLIGHT             = 210 // Change to/from inverted flight
	MAV_CMD_DO_MOUNT_CONTROL_QUAT          = 220 // Mission command to control a camera or antenna mount, using a quaternion as reference.
	MAV_CMD_DO_GUIDED_MASTER               = 221 // set id of master controller
	MAV_CMD_DO_GUIDED_LIMITS               = 222 // set limits for external control
	MAV_CMD_DO_LAST                        = 240 // NOP - This command is only used to mark the upper limit of the DO commands in the enumeration
	MAV_CMD_PREFLIGHT_CALIBRATION          = 241 // Trigger calibration. This command will be only accepted if in pre-flight mode.
	MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS   = 242 // Set sensor offsets. This command will be only accepted if in pre-flight mode.
	MAV_CMD_PREFLIGHT_UAVCAN               = 243 // Trigger UAVCAN config. This command will be only accepted if in pre-flight mode.
	MAV_CMD_PREFLIGHT_STORAGE              = 245 // Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.
	MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN      = 246 // Request the reboot or shutdown of system components.
	MAV_CMD_OVERRIDE_GOTO                  = 252 // Hold / continue the current action
	MAV_CMD_MISSION_START                  = 55  // start running a mission
	MAV_CMD_COMPONENT_ARM_DISARM           = 56  // Arms / Disarms a component
	MAV_CMD_GET_HOME_POSITION              = 57  // Request the home position from the vehicle.
	MAV_CMD_START_RX_PAIR                  = 58  // Starts receiver pairing
	MAV_CMD_GET_MESSAGE_INTERVAL           = 59  // Request the interval between messages for a particular MAVLink message ID
	MAV_CMD_SET_MESSAGE_INTERVAL           = 60  // Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM
	MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 61  // Request autopilot capabilities
	MAV_CMD_IMAGE_START_CAPTURE            = 62  // Start image capture sequence
	MAV_CMD_IMAGE_STOP_CAPTURE             = 63  // Stop image capture sequence
	MAV_CMD_DO_TRIGGER_CONTROL             = 64  // Enable or disable on-board camera triggering system.
	MAV_CMD_VIDEO_START_CAPTURE            = 65  // Starts video capture
	MAV_CMD_VIDEO_STOP_CAPTURE             = 66  // Stop the current video capture
	MAV_CMD_PANORAMA_CREATE                = 67  // Create a panorama at the current position
	MAV_CMD_DO_VTOL_TRANSITION             = 68  // Request VTOL transition
	MAV_CMD_PAYLOAD_PREPARE_DEPLOY         = 69  // Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.
	MAV_CMD_PAYLOAD_CONTROL_DEPLOY         = 70  // Control the payload deployment.
)

MavCmd: Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data.

View Source
const (
	MAV_DATA_STREAM_ALL             = 0  // Enable all data streams
	MAV_DATA_STREAM_RAW_SENSORS     = 1  // Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.
	MAV_DATA_STREAM_EXTENDED_STATUS = 2  // Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS
	MAV_DATA_STREAM_RC_CHANNELS     = 3  // Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW
	MAV_DATA_STREAM_RAW_CONTROLLER  = 4  // Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.
	MAV_DATA_STREAM_POSITION        = 6  // Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.
	MAV_DATA_STREAM_EXTRA1          = 10 // Dependent on the autopilot
	MAV_DATA_STREAM_EXTRA2          = 11 // Dependent on the autopilot
	MAV_DATA_STREAM_EXTRA3          = 12 // Dependent on the autopilot
)

MavDataStream: THIS INTERFACE IS DEPRECATED AS OF JULY 2015. Please use MESSAGE_INTERVAL instead. A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages.

View Source
const (
	MAV_ROI_NONE     = 0 // No region of interest.
	MAV_ROI_WPNEXT   = 1 // Point toward next MISSION.
	MAV_ROI_WPINDEX  = 2 // Point toward given MISSION.
	MAV_ROI_LOCATION = 3 // Point toward fixed location.
	MAV_ROI_TARGET   = 4 // Point toward of given id.
)

MavRoi: The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI).

View Source
const (
	MAV_CMD_ACK_OK                                 = 0 // Command / mission item is ok.
	MAV_CMD_ACK_ERR_FAIL                           = 1 // Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.
	MAV_CMD_ACK_ERR_ACCESS_DENIED                  = 2 // The system is refusing to accept this command from this source / communication partner.
	MAV_CMD_ACK_ERR_NOT_SUPPORTED                  = 3 // Command or mission item is not supported, other commands would be accepted.
	MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED = 4 // The coordinate frame of this command / mission item is not supported.
	MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE       = 5 // The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible.
	MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE             = 6 // The X or latitude value is out of range.
	MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE             = 7 // The Y or longitude value is out of range.
	MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE             = 8 // The Z or altitude value is out of range.
)

MavCmdAck: ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission.

View Source
const (
	MAV_PARAM_TYPE_UINT8  = 1  // 8-bit unsigned integer
	MAV_PARAM_TYPE_INT8   = 2  // 8-bit signed integer
	MAV_PARAM_TYPE_UINT16 = 3  // 16-bit unsigned integer
	MAV_PARAM_TYPE_INT16  = 4  // 16-bit signed integer
	MAV_PARAM_TYPE_UINT32 = 5  // 32-bit unsigned integer
	MAV_PARAM_TYPE_INT32  = 6  // 32-bit signed integer
	MAV_PARAM_TYPE_UINT64 = 7  // 64-bit unsigned integer
	MAV_PARAM_TYPE_INT64  = 8  // 64-bit signed integer
	MAV_PARAM_TYPE_REAL32 = 9  // 32-bit floating-point
	MAV_PARAM_TYPE_REAL64 = 10 // 64-bit floating-point
)

MavParamType: Specifies the datatype of a MAVLink parameter.

View Source
const (
	MAV_RESULT_ACCEPTED             = 0 // Command ACCEPTED and EXECUTED
	MAV_RESULT_TEMPORARILY_REJECTED = 1 // Command TEMPORARY REJECTED/DENIED
	MAV_RESULT_DENIED               = 2 // Command PERMANENTLY DENIED
	MAV_RESULT_UNSUPPORTED          = 3 // Command UNKNOWN/UNSUPPORTED
	MAV_RESULT_FAILED               = 4 // Command executed, but failed
)

MavResult: result from a mavlink command

View Source
const (
	MAV_MISSION_ACCEPTED          = 0  // mission accepted OK
	MAV_MISSION_ERROR             = 1  // generic error / not accepting mission commands at all right now
	MAV_MISSION_UNSUPPORTED_FRAME = 2  // coordinate frame is not supported
	MAV_MISSION_UNSUPPORTED       = 3  // command is not supported
	MAV_MISSION_NO_SPACE          = 4  // mission item exceeds storage space
	MAV_MISSION_INVALID           = 5  // one of the parameters has an invalid value
	MAV_MISSION_INVALID_PARAM1    = 6  // param1 has an invalid value
	MAV_MISSION_INVALID_PARAM2    = 7  // param2 has an invalid value
	MAV_MISSION_INVALID_PARAM3    = 8  // param3 has an invalid value
	MAV_MISSION_INVALID_PARAM4    = 9  // param4 has an invalid value
	MAV_MISSION_INVALID_PARAM5_X  = 10 // x/param5 has an invalid value
	MAV_MISSION_INVALID_PARAM6_Y  = 11 // y/param6 has an invalid value
	MAV_MISSION_INVALID_PARAM7    = 12 // param7 has an invalid value
	MAV_MISSION_INVALID_SEQUENCE  = 13 // received waypoint out of sequence
	MAV_MISSION_DENIED            = 14 // not accepting any mission commands from this communication partner
)

MavMissionResult: result in a mavlink mission ack

View Source
const (
	MAV_SEVERITY_EMERGENCY = 0 // System is unusable. This is a "panic" condition.
	MAV_SEVERITY_ALERT     = 1 // Action should be taken immediately. Indicates error in non-critical systems.
	MAV_SEVERITY_CRITICAL  = 2 // Action must be taken immediately. Indicates failure in a primary system.
	MAV_SEVERITY_ERROR     = 3 // Indicates an error in secondary/redundant systems.
	MAV_SEVERITY_WARNING   = 4 // Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.
	MAV_SEVERITY_NOTICE    = 5 // An unusual event has occured, though not an error condition. This should be investigated for the root cause.
	MAV_SEVERITY_INFO      = 6 // Normal operational messages. Useful for logging. No action is required for these messages.
	MAV_SEVERITY_DEBUG     = 7 // Useful non-operational messages that can assist in debugging. These should not occur during normal operation.
)

MavSeverity: Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/.

View Source
const (
	MAV_POWER_STATUS_BRICK_VALID                = 1  // main brick power supply valid
	MAV_POWER_STATUS_SERVO_VALID                = 2  // main servo power supply valid for FMU
	MAV_POWER_STATUS_USB_CONNECTED              = 4  // USB power is connected
	MAV_POWER_STATUS_PERIPH_OVERCURRENT         = 8  // peripheral supply is in over-current state
	MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 // hi-power peripheral supply is in over-current state
	MAV_POWER_STATUS_CHANGED                    = 32 // Power status has changed since boot
)

MavPowerStatus: Power supply status flags (bitmask)

View Source
const (
	SERIAL_CONTROL_DEV_TELEM1 = 0  // First telemetry port
	SERIAL_CONTROL_DEV_TELEM2 = 1  // Second telemetry port
	SERIAL_CONTROL_DEV_GPS1   = 2  // First GPS port
	SERIAL_CONTROL_DEV_GPS2   = 3  // Second GPS port
	SERIAL_CONTROL_DEV_SHELL  = 10 // system shell
)

SerialControlDev: SERIAL_CONTROL device types

View Source
const (
	SERIAL_CONTROL_FLAG_REPLY     = 1  // Set if this is a reply
	SERIAL_CONTROL_FLAG_RESPOND   = 2  // Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message
	SERIAL_CONTROL_FLAG_EXCLUSIVE = 4  // Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set
	SERIAL_CONTROL_FLAG_BLOCKING  = 8  // Block on writes to the serial port
	SERIAL_CONTROL_FLAG_MULTI     = 16 // Send multiple replies until port is drained
)

SerialControlFlag: SERIAL_CONTROL flags (bitmask)

View Source
const (
	MAV_DISTANCE_SENSOR_LASER      = 0 // Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units
	MAV_DISTANCE_SENSOR_ULTRASOUND = 1 // Ultrasound rangefinder, e.g. MaxBotix units
	MAV_DISTANCE_SENSOR_INFRARED   = 2 // Infrared rangefinder, e.g. Sharp units
)

MavDistanceSensor: Enumeration of distance sensor types

View Source
const (
	MAV_SENSOR_ROTATION_NONE                       = 0  // Roll: 0, Pitch: 0, Yaw: 0
	MAV_SENSOR_ROTATION_YAW_45                     = 1  // Roll: 0, Pitch: 0, Yaw: 45
	MAV_SENSOR_ROTATION_YAW_90                     = 2  // Roll: 0, Pitch: 0, Yaw: 90
	MAV_SENSOR_ROTATION_YAW_135                    = 3  // Roll: 0, Pitch: 0, Yaw: 135
	MAV_SENSOR_ROTATION_YAW_180                    = 4  // Roll: 0, Pitch: 0, Yaw: 180
	MAV_SENSOR_ROTATION_YAW_225                    = 5  // Roll: 0, Pitch: 0, Yaw: 225
	MAV_SENSOR_ROTATION_YAW_270                    = 6  // Roll: 0, Pitch: 0, Yaw: 270
	MAV_SENSOR_ROTATION_YAW_315                    = 7  // Roll: 0, Pitch: 0, Yaw: 315
	MAV_SENSOR_ROTATION_ROLL_180                   = 8  // Roll: 180, Pitch: 0, Yaw: 0
	MAV_SENSOR_ROTATION_ROLL_180_YAW_45            = 9  // Roll: 180, Pitch: 0, Yaw: 45
	MAV_SENSOR_ROTATION_ROLL_180_YAW_90            = 10 // Roll: 180, Pitch: 0, Yaw: 90
	MAV_SENSOR_ROTATION_ROLL_180_YAW_135           = 11 // Roll: 180, Pitch: 0, Yaw: 135
	MAV_SENSOR_ROTATION_PITCH_180                  = 12 // Roll: 0, Pitch: 180, Yaw: 0
	MAV_SENSOR_ROTATION_ROLL_180_YAW_225           = 13 // Roll: 180, Pitch: 0, Yaw: 225
	MAV_SENSOR_ROTATION_ROLL_180_YAW_270           = 14 // Roll: 180, Pitch: 0, Yaw: 270
	MAV_SENSOR_ROTATION_ROLL_180_YAW_315           = 15 // Roll: 180, Pitch: 0, Yaw: 315
	MAV_SENSOR_ROTATION_ROLL_90                    = 16 // Roll: 90, Pitch: 0, Yaw: 0
	MAV_SENSOR_ROTATION_ROLL_90_YAW_45             = 17 // Roll: 90, Pitch: 0, Yaw: 45
	MAV_SENSOR_ROTATION_ROLL_90_YAW_90             = 18 // Roll: 90, Pitch: 0, Yaw: 90
	MAV_SENSOR_ROTATION_ROLL_90_YAW_135            = 19 // Roll: 90, Pitch: 0, Yaw: 135
	MAV_SENSOR_ROTATION_ROLL_270                   = 20 // Roll: 270, Pitch: 0, Yaw: 0
	MAV_SENSOR_ROTATION_ROLL_270_YAW_45            = 21 // Roll: 270, Pitch: 0, Yaw: 45
	MAV_SENSOR_ROTATION_ROLL_270_YAW_90            = 22 // Roll: 270, Pitch: 0, Yaw: 90
	MAV_SENSOR_ROTATION_ROLL_270_YAW_135           = 23 // Roll: 270, Pitch: 0, Yaw: 135
	MAV_SENSOR_ROTATION_PITCH_90                   = 24 // Roll: 0, Pitch: 90, Yaw: 0
	MAV_SENSOR_ROTATION_PITCH_270                  = 25 // Roll: 0, Pitch: 270, Yaw: 0
	MAV_SENSOR_ROTATION_PITCH_180_YAW_90           = 26 // Roll: 0, Pitch: 180, Yaw: 90
	MAV_SENSOR_ROTATION_PITCH_180_YAW_270          = 27 // Roll: 0, Pitch: 180, Yaw: 270
	MAV_SENSOR_ROTATION_ROLL_90_PITCH_90           = 28 // Roll: 90, Pitch: 90, Yaw: 0
	MAV_SENSOR_ROTATION_ROLL_180_PITCH_90          = 29 // Roll: 180, Pitch: 90, Yaw: 0
	MAV_SENSOR_ROTATION_ROLL_270_PITCH_90          = 30 // Roll: 270, Pitch: 90, Yaw: 0
	MAV_SENSOR_ROTATION_ROLL_90_PITCH_180          = 31 // Roll: 90, Pitch: 180, Yaw: 0
	MAV_SENSOR_ROTATION_ROLL_270_PITCH_180         = 32 // Roll: 270, Pitch: 180, Yaw: 0
	MAV_SENSOR_ROTATION_ROLL_90_PITCH_270          = 33 // Roll: 90, Pitch: 270, Yaw: 0
	MAV_SENSOR_ROTATION_ROLL_180_PITCH_270         = 34 // Roll: 180, Pitch: 270, Yaw: 0
	MAV_SENSOR_ROTATION_ROLL_270_PITCH_270         = 35 // Roll: 270, Pitch: 270, Yaw: 0
	MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90   = 36 // Roll: 90, Pitch: 180, Yaw: 90
	MAV_SENSOR_ROTATION_ROLL_90_YAW_270            = 37 // Roll: 90, Pitch: 0, Yaw: 270
	MAV_SENSOR_ROTATION_ROLL_315_PITCH_315_YAW_315 = 38 // Roll: 315, Pitch: 315, Yaw: 315
)

MavSensorOrientation: Enumeration of sensor orientation, according to its rotations

View Source
const (
	MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT                  = 1   // Autopilot supports MISSION float message type.
	MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT                    = 2   // Autopilot supports the new param float message type.
	MAV_PROTOCOL_CAPABILITY_MISSION_INT                    = 4   // Autopilot supports MISSION_INT scaled integer message type.
	MAV_PROTOCOL_CAPABILITY_COMMAND_INT                    = 8   // Autopilot supports COMMAND_INT scaled integer message type.
	MAV_PROTOCOL_CAPABILITY_PARAM_UNION                    = 16  // Autopilot supports the new param union message type.
	MAV_PROTOCOL_CAPABILITY_FTP                            = 32  // Autopilot supports the new param union message type.
	MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET            = 64  // Autopilot supports commanding attitude offboard.
	MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED  = 128 // Autopilot supports commanding position and velocity targets in local NED frame.
	MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 8   // Autopilot supports commanding position and velocity targets in global scaled integers.
	MAV_PROTOCOL_CAPABILITY_TERRAIN                        = 9   // Autopilot supports terrain protocol / data handling.
	MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET            = 10  // Autopilot supports direct actuator control.
	MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION             = 11  // Autopilot supports the flight termination command.
	MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION            = 12  // Autopilot supports onboard compass calibration.
)

MavProtocolCapability: Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability.

View Source
const (
	MAV_ESTIMATOR_TYPE_NAIVE   = 1 // This is a naive estimator without any real covariance feedback.
	MAV_ESTIMATOR_TYPE_VISION  = 2 // Computer vision based estimate. Might be up to scale.
	MAV_ESTIMATOR_TYPE_VIO     = 3 // Visual-inertial estimate.
	MAV_ESTIMATOR_TYPE_GPS     = 4 // Plain GPS estimate.
	MAV_ESTIMATOR_TYPE_GPS_INS = 5 // Estimator integrating GPS and inertial sensing.
)

MavEstimatorType: Enumeration of estimator types

View Source
const (
	MAV_BATTERY_TYPE_UNKNOWN = 0 // Not specified.
	MAV_BATTERY_TYPE_LIPO    = 1 // Lithium polymere battery
	MAV_BATTERY_TYPE_LIFE    = 2 // Lithium ferrite battery
	MAV_BATTERY_TYPE_LION    = 3 // Lithium-ION battery
	MAV_BATTERY_TYPE_NIMH    = 4 // Nickel metal hydride battery
)

MavBatteryType: Enumeration of battery types

View Source
const (
	MAV_BATTERY_FUNCTION_UNKNOWN    = 0 // Lithium polymere battery
	MAV_BATTERY_FUNCTION_ALL        = 1 // Battery supports all flight systems
	MAV_BATTERY_FUNCTION_PROPULSION = 2 // Battery for the propulsion system
	MAV_BATTERY_FUNCTION_AVIONICS   = 3 // Avionics battery
	MAV_BATTERY_TYPE_PAYLOAD        = 4 // Payload battery
)

MavBatteryFunction: Enumeration of battery functions

View Source
const (
	MAV_VTOL_STATE_UNDEFINED        = 0 // MAV is not configured as VTOL
	MAV_VTOL_STATE_TRANSITION_TO_FW = 1 // VTOL is in transition from multicopter to fixed-wing
	MAV_VTOL_STATE_TRANSITION_TO_MC = 2 // VTOL is in transition from fixed-wing to multicopter
	MAV_VTOL_STATE_MC               = 3 // VTOL is in multicopter state
	MAV_VTOL_STATE_FW               = 4 // VTOL is in fixed-wing state
)

MavVtolState: Enumeration of VTOL states

View Source
const (
	MAV_LANDED_STATE_UNDEFINED = 0 // MAV landed state is unknown
	MAV_LANDED_STATE_ON_GROUND = 1 // MAV is landed (on ground)
	MAV_LANDED_STATE_IN_AIR    = 2 // MAV is in air
)

MavLandedState: Enumeration of landed detector states

View Source
const (
	ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0 // Altitude reported from a Baro source using QNH reference
	ADSB_ALTITUDE_TYPE_GEOMETRIC    = 1 // Altitude reported from a GNSS source
)

AdsbAltitudeType: Enumeration of the ADSB altimeter types

View Source
const (
	ADSB_EMITTER_TYPE_NO_INFO           = 0  //
	ADSB_EMITTER_TYPE_LIGHT             = 1  //
	ADSB_EMITTER_TYPE_SMALL             = 2  //
	ADSB_EMITTER_TYPE_LARGE             = 3  //
	ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4  //
	ADSB_EMITTER_TYPE_HEAVY             = 5  //
	ADSB_EMITTER_TYPE_HIGHLY_MANUV      = 6  //
	ADSB_EMITTER_TYPE_ROTOCRAFT         = 7  //
	ADSB_EMITTER_TYPE_UNASSIGNED        = 8  //
	ADSB_EMITTER_TYPE_GLIDER            = 9  //
	ADSB_EMITTER_TYPE_LIGHTER_AIR       = 10 //
	ADSB_EMITTER_TYPE_PARACHUTE         = 11 //
	ADSB_EMITTER_TYPE_ULTRA_LIGHT       = 12 //
	ADSB_EMITTER_TYPE_UNASSIGNED2       = 13 //
	ADSB_EMITTER_TYPE_UAV               = 14 //
	ADSB_EMITTER_TYPE_SPACE             = 15 //
	ADSB_EMITTER_TYPE_UNASSGINED3       = 16 //
	ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17 //
	ADSB_EMITTER_TYPE_SERVICE_SURFACE   = 18 //
	ADSB_EMITTER_TYPE_POINT_OBSTACLE    = 19 //
)

AdsbEmitterType: ADSB classification for the type of vehicle emitting the transponder signal

View Source
const (
	ADSB_DATA_VALID_FLAGS_VALID_COORDS   = 1   //
	ADSB_DATA_VALID_FLAGS_VALID_ALTITUDE = 2   //
	ADSB_DATA_VALID_FLAGS_VALID_HEADING  = 4   //
	ADSB_DATA_VALID_FLAGS_VALID_VELOCITY = 8   //
	ADSB_DATA_VALID_FLAGS_VALID_CALLSIGN = 16  //
	ADSB_DATA_VALID_FLAGS_RFU_1          = 32  //
	ADSB_DATA_VALID_FLAGS_RFU_2          = 64  //
	ADSB_DATA_VALID_FLAGS_RFU_3          = 128 //
)

AdsbDataValidFlags: These flags indicate data validity of each data source. Set = data valid

View Source
const (
	MSG_ID_HEARTBEAT                               = 0
	MSG_ID_SYS_STATUS                              = 1
	MSG_ID_SYSTEM_TIME                             = 2
	MSG_ID_PING                                    = 4
	MSG_ID_CHANGE_OPERATOR_CONTROL                 = 5
	MSG_ID_CHANGE_OPERATOR_CONTROL_ACK             = 6
	MSG_ID_AUTH_KEY                                = 7
	MSG_ID_SET_MODE                                = 11
	MSG_ID_PARAM_REQUEST_READ                      = 20
	MSG_ID_PARAM_REQUEST_LIST                      = 21
	MSG_ID_PARAM_VALUE                             = 22
	MSG_ID_PARAM_SET                               = 23
	MSG_ID_GPS_RAW_INT                             = 24
	MSG_ID_GPS_STATUS                              = 25
	MSG_ID_SCALED_IMU                              = 26
	MSG_ID_RAW_IMU                                 = 27
	MSG_ID_RAW_PRESSURE                            = 28
	MSG_ID_SCALED_PRESSURE                         = 29
	MSG_ID_ATTITUDE                                = 30
	MSG_ID_ATTITUDE_QUATERNION                     = 31
	MSG_ID_LOCAL_POSITION_NED                      = 32
	MSG_ID_GLOBAL_POSITION_INT                     = 33
	MSG_ID_RC_CHANNELS_SCALED                      = 34
	MSG_ID_RC_CHANNELS_RAW                         = 35
	MSG_ID_SERVO_OUTPUT_RAW                        = 36
	MSG_ID_MISSION_REQUEST_PARTIAL_LIST            = 37
	MSG_ID_MISSION_WRITE_PARTIAL_LIST              = 38
	MSG_ID_MISSION_ITEM                            = 39
	MSG_ID_MISSION_REQUEST                         = 40
	MSG_ID_MISSION_SET_CURRENT                     = 41
	MSG_ID_MISSION_CURRENT                         = 42
	MSG_ID_MISSION_REQUEST_LIST                    = 43
	MSG_ID_MISSION_COUNT                           = 44
	MSG_ID_MISSION_CLEAR_ALL                       = 45
	MSG_ID_MISSION_ITEM_REACHED                    = 46
	MSG_ID_MISSION_ACK                             = 47
	MSG_ID_SET_GPS_GLOBAL_ORIGIN                   = 48
	MSG_ID_GPS_GLOBAL_ORIGIN                       = 49
	MSG_ID_PARAM_MAP_RC                            = 50
	MSG_ID_SAFETY_SET_ALLOWED_AREA                 = 54
	MSG_ID_SAFETY_ALLOWED_AREA                     = 55
	MSG_ID_ATTITUDE_QUATERNION_COV                 = 61
	MSG_ID_NAV_CONTROLLER_OUTPUT                   = 62
	MSG_ID_GLOBAL_POSITION_INT_COV                 = 63
	MSG_ID_LOCAL_POSITION_NED_COV                  = 64
	MSG_ID_RC_CHANNELS                             = 65
	MSG_ID_REQUEST_DATA_STREAM                     = 66
	MSG_ID_DATA_STREAM                             = 67
	MSG_ID_MANUAL_CONTROL                          = 69
	MSG_ID_RC_CHANNELS_OVERRIDE                    = 70
	MSG_ID_MISSION_ITEM_INT                        = 73
	MSG_ID_VFR_HUD                                 = 74
	MSG_ID_COMMAND_INT                             = 75
	MSG_ID_COMMAND_LONG                            = 76
	MSG_ID_COMMAND_ACK                             = 77
	MSG_ID_MANUAL_SETPOINT                         = 81
	MSG_ID_SET_ATTITUDE_TARGET                     = 82
	MSG_ID_ATTITUDE_TARGET                         = 83
	MSG_ID_SET_POSITION_TARGET_LOCAL_NED           = 84
	MSG_ID_POSITION_TARGET_LOCAL_NED               = 85
	MSG_ID_SET_POSITION_TARGET_GLOBAL_INT          = 86
	MSG_ID_POSITION_TARGET_GLOBAL_INT              = 87
	MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET = 89
	MSG_ID_HIL_STATE                               = 90
	MSG_ID_HIL_CONTROLS                            = 91
	MSG_ID_HIL_RC_INPUTS_RAW                       = 92
	MSG_ID_OPTICAL_FLOW                            = 100
	MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE         = 101
	MSG_ID_VISION_POSITION_ESTIMATE                = 102
	MSG_ID_VISION_SPEED_ESTIMATE                   = 103
	MSG_ID_VICON_POSITION_ESTIMATE                 = 104
	MSG_ID_HIGHRES_IMU                             = 105
	MSG_ID_OPTICAL_FLOW_RAD                        = 106
	MSG_ID_HIL_SENSOR                              = 107
	MSG_ID_SIM_STATE                               = 108
	MSG_ID_RADIO_STATUS                            = 109
	MSG_ID_FILE_TRANSFER_PROTOCOL                  = 110
	MSG_ID_TIMESYNC                                = 111
	MSG_ID_CAMERA_TRIGGER                          = 112
	MSG_ID_HIL_GPS                                 = 113
	MSG_ID_HIL_OPTICAL_FLOW                        = 114
	MSG_ID_HIL_STATE_QUATERNION                    = 115
	MSG_ID_SCALED_IMU2                             = 116
	MSG_ID_LOG_REQUEST_LIST                        = 117
	MSG_ID_LOG_ENTRY                               = 118
	MSG_ID_LOG_REQUEST_DATA                        = 119
	MSG_ID_LOG_DATA                                = 120
	MSG_ID_LOG_ERASE                               = 121
	MSG_ID_LOG_REQUEST_END                         = 122
	MSG_ID_GPS_INJECT_DATA                         = 123
	MSG_ID_GPS2_RAW                                = 124
	MSG_ID_POWER_STATUS                            = 125
	MSG_ID_SERIAL_CONTROL                          = 126
	MSG_ID_GPS_RTK                                 = 127
	MSG_ID_GPS2_RTK                                = 128
	MSG_ID_SCALED_IMU3                             = 129
	MSG_ID_DATA_TRANSMISSION_HANDSHAKE             = 130
	MSG_ID_ENCAPSULATED_DATA                       = 131
	MSG_ID_DISTANCE_SENSOR                         = 132
	MSG_ID_TERRAIN_REQUEST                         = 133
	MSG_ID_TERRAIN_DATA                            = 134
	MSG_ID_TERRAIN_CHECK                           = 135
	MSG_ID_TERRAIN_REPORT                          = 136
	MSG_ID_SCALED_PRESSURE2                        = 137
	MSG_ID_ATT_POS_MOCAP                           = 138
	MSG_ID_SET_ACTUATOR_CONTROL_TARGET             = 139
	MSG_ID_ACTUATOR_CONTROL_TARGET                 = 140
	MSG_ID_ALTITUDE                                = 141
	MSG_ID_RESOURCE_REQUEST                        = 142
	MSG_ID_SCALED_PRESSURE3                        = 143
	MSG_ID_CONTROL_SYSTEM_STATE                    = 146
	MSG_ID_BATTERY_STATUS                          = 147
	MSG_ID_AUTOPILOT_VERSION                       = 148
	MSG_ID_LANDING_TARGET                          = 149
	MSG_ID_VIBRATION                               = 241
	MSG_ID_HOME_POSITION                           = 242
	MSG_ID_SET_HOME_POSITION                       = 243
	MSG_ID_MESSAGE_INTERVAL                        = 244
	MSG_ID_EXTENDED_SYS_STATE                      = 245
	MSG_ID_ADSB_VEHICLE                            = 246
	MSG_ID_V2_EXTENSION                            = 248
	MSG_ID_MEMORY_VECT                             = 249
	MSG_ID_DEBUG_VECT                              = 250
	MSG_ID_NAMED_VALUE_FLOAT                       = 251
	MSG_ID_NAMED_VALUE_INT                         = 252
	MSG_ID_STATUSTEXT                              = 253
	MSG_ID_DEBUG                                   = 254
)

Message IDs

View Source
const (
	MAV_PFS_CMD_READ_ALL       = 0 // Read all parameters from storage
	MAV_PFS_CMD_WRITE_ALL      = 1 // Write all parameters to storage
	MAV_PFS_CMD_CLEAR_ALL      = 2 // Clear all  parameters in storage
	MAV_PFS_CMD_READ_SPECIFIC  = 3 // Read specific parameters from storage
	MAV_PFS_CMD_WRITE_SPECIFIC = 4 // Write specific parameters to storage
	MAV_PFS_CMD_CLEAR_SPECIFIC = 5 // Clear specific parameters in storage
	MAV_PFS_CMD_DO_NOTHING     = 6 // do nothing
)

MavPreflightStorageAction: Action required when performing CMD_PREFLIGHT_STORAGE

View Source
const (
	MSG_ID_FLEXIFUNCTION_SET                 = 150
	MSG_ID_FLEXIFUNCTION_READ_REQ            = 151
	MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION     = 152
	MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK = 153
	MSG_ID_FLEXIFUNCTION_DIRECTORY           = 155
	MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK       = 156
	MSG_ID_FLEXIFUNCTION_COMMAND             = 157
	MSG_ID_FLEXIFUNCTION_COMMAND_ACK         = 158
	MSG_ID_SERIAL_UDB_EXTRA_F2_A             = 170
	MSG_ID_SERIAL_UDB_EXTRA_F2_B             = 171
	MSG_ID_SERIAL_UDB_EXTRA_F4               = 172
	MSG_ID_SERIAL_UDB_EXTRA_F5               = 173
	MSG_ID_SERIAL_UDB_EXTRA_F6               = 174
	MSG_ID_SERIAL_UDB_EXTRA_F7               = 175
	MSG_ID_SERIAL_UDB_EXTRA_F8               = 176
	MSG_ID_SERIAL_UDB_EXTRA_F13              = 177
	MSG_ID_SERIAL_UDB_EXTRA_F14              = 178
	MSG_ID_SERIAL_UDB_EXTRA_F15              = 179
	MSG_ID_SERIAL_UDB_EXTRA_F16              = 180
	MSG_ID_ALTITUDES                         = 181
	MSG_ID_AIRSPEEDS                         = 182
)

Message IDs

View Source
const (
	DATA_TYPE_JPEG_IMAGE = 1 //
	DATA_TYPE_RAW_IMAGE  = 2 //
	DATA_TYPE_KINECT     = 3 //
)

DataTypes: Content Types for data transmission handshake

View Source
const (
	MAV_CMD_DO_START_SEARCH  = 0 // Starts a search
	MAV_CMD_DO_FINISH_SEARCH = 1 // Starts a search
	MAV_CMD_NAV_SWEEP        = 2 // Starts a search
)

MavCmd:

View Source
const (
	MSG_ID_SET_CAM_SHUTTER              = 151
	MSG_ID_IMAGE_TRIGGERED              = 152
	MSG_ID_IMAGE_TRIGGER_CONTROL        = 153
	MSG_ID_IMAGE_AVAILABLE              = 154
	MSG_ID_SET_POSITION_CONTROL_OFFSET  = 160
	MSG_ID_POSITION_CONTROL_SETPOINT    = 170
	MSG_ID_MARKER                       = 171
	MSG_ID_RAW_AUX                      = 172
	MSG_ID_WATCHDOG_HEARTBEAT           = 180
	MSG_ID_WATCHDOG_PROCESS_INFO        = 181
	MSG_ID_WATCHDOG_PROCESS_STATUS      = 182
	MSG_ID_WATCHDOG_COMMAND             = 183
	MSG_ID_PATTERN_DETECTED             = 190
	MSG_ID_POINT_OF_INTEREST            = 191
	MSG_ID_POINT_OF_INTEREST_CONNECTION = 192
	MSG_ID_BRIEF_FEATURE                = 195
	MSG_ID_ATTITUDE_CONTROL             = 200
	MSG_ID_DETECTION_STATS              = 205
	MSG_ID_ONBOARD_HEALTH               = 206
)

Message IDs

View Source
const (
	MODE_MANUAL_DIRECT = 0 // Raw input pulse widts sent to output
	MODE_MANUAL_SCALED = 1 // Inputs are normalized using calibration, the converted back to raw pulse widths for output
	MODE_AUTO_PID_ATT  = 2 //  dfsdfs
	MODE_AUTO_PID_VEL  = 3 //  dfsfds
	MODE_AUTO_PID_POS  = 4 //  dfsdfsdfs
)

UalbertaAutopilotMode: Available autopilot modes for ualberta uav

View Source
const (
	NAV_AHRS_INIT    = 0 //
	NAV_AHRS         = 1 // AHRS mode
	NAV_INS_GPS_INIT = 2 // INS/GPS initialization mode
	NAV_INS_GPS      = 3 // INS/GPS mode
)

UalbertaNavMode: Navigation filter mode

View Source
const (
	PILOT_MANUAL = 0 //  sdf
	PILOT_AUTO   = 1 //  dfs
	PILOT_ROTO   = 2 //  Rotomotion mode
)

UalbertaPilotMode: Mode currently commanded by pilot

View Source
const (
	MSG_ID_NAV_FILTER_BIAS     = 220
	MSG_ID_RADIO_CALIBRATION   = 221
	MSG_ID_UALBERTA_SYS_STATUS = 222
)

Message IDs

View Source
const (
	FACTORY_TEST_AXIS_RANGE_LIMITS = 0 // Tests to make sure each axis can move to its mechanical limits
)

FactoryTest:

View Source
const (
	MAV_CMD_PREFLIGHT_STORAGE_ADVANCED = 0 // Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.
)

MavCmd:

Variables

View Source
var (
	ErrUnknownMsgID = errors.New("unknown msg id")
	ErrCrcFail      = errors.New("checksum did not match")
)

Functions

This section is empty.

Types

type ActuatorControlTarget

type ActuatorControlTarget struct {
	TimeUsec uint64     // Timestamp (micros since boot or Unix epoch)
	Controls [8]float32 // Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.
	GroupMlx uint8      // Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.
}

Set the vehicle attitude and body angular rates.

func (*ActuatorControlTarget) MsgID

func (self *ActuatorControlTarget) MsgID() uint8

func (*ActuatorControlTarget) MsgName

func (self *ActuatorControlTarget) MsgName() string

func (*ActuatorControlTarget) Pack

func (self *ActuatorControlTarget) Pack(p *Packet) error

func (*ActuatorControlTarget) Unpack

func (self *ActuatorControlTarget) Unpack(p *Packet) error

type AdsbVehicle

type AdsbVehicle struct {
	IcaoAddress  uint32  // ICAO Address
	Lat          float32 // The reported lattitude in degrees
	Lon          float32 // The reported longitude in degrees
	Altitude     float32 // Altitude(ASL) in meters
	HorVelocity  float32 // The horizontal velocity in meters/second
	VerVelocity  float32 // The vertical velocity in meters/second
	Heading      uint16  // Course over ground in degrees * 10^2
	AltitudeType uint8   // Type from ADSB_ALTITUDE_TYPE enum.
	Callsign     [9]byte // The callsign(squawk)
	Emittertype  uint8   // Type from ADSB_EMITTER_CATEGORY_TYPE enum
	Tslc         uint8   // Time since last communication in seconds
	Validflags   uint8   // Flags to Indicate valid data fields
}

The location and information of a ADSB vehicle

func (*AdsbVehicle) MsgID

func (self *AdsbVehicle) MsgID() uint8

func (*AdsbVehicle) MsgName

func (self *AdsbVehicle) MsgName() string

func (*AdsbVehicle) Pack

func (self *AdsbVehicle) Pack(p *Packet) error

func (*AdsbVehicle) Unpack

func (self *AdsbVehicle) Unpack(p *Packet) error

type Ahrs

type Ahrs struct {
	Omegaix     float32 // X gyro drift estimate rad/s
	Omegaiy     float32 // Y gyro drift estimate rad/s
	Omegaiz     float32 // Z gyro drift estimate rad/s
	AccelWeight float32 // average accel_weight
	RenormVal   float32 // average renormalisation value
	ErrorRp     float32 // average error_roll_pitch value
	ErrorYaw    float32 // average error_yaw value
}

Status of DCM attitude estimator

func (*Ahrs) MsgID

func (self *Ahrs) MsgID() uint8

func (*Ahrs) MsgName

func (self *Ahrs) MsgName() string

func (*Ahrs) Pack

func (self *Ahrs) Pack(p *Packet) error

func (*Ahrs) Unpack

func (self *Ahrs) Unpack(p *Packet) error

type Ahrs2

type Ahrs2 struct {
	Roll     float32 // Roll angle (rad)
	Pitch    float32 // Pitch angle (rad)
	Yaw      float32 // Yaw angle (rad)
	Altitude float32 // Altitude (MSL)
	Lat      int32   // Latitude in degrees * 1E7
	Lng      int32   // Longitude in degrees * 1E7
}

Status of secondary AHRS filter if available

func (*Ahrs2) MsgID

func (self *Ahrs2) MsgID() uint8

func (*Ahrs2) MsgName

func (self *Ahrs2) MsgName() string

func (*Ahrs2) Pack

func (self *Ahrs2) Pack(p *Packet) error

func (*Ahrs2) Unpack

func (self *Ahrs2) Unpack(p *Packet) error

type Ahrs3

type Ahrs3 struct {
	Roll     float32 // Roll angle (rad)
	Pitch    float32 // Pitch angle (rad)
	Yaw      float32 // Yaw angle (rad)
	Altitude float32 // Altitude (MSL)
	Lat      int32   // Latitude in degrees * 1E7
	Lng      int32   // Longitude in degrees * 1E7
	V1       float32 // test variable1
	V2       float32 // test variable2
	V3       float32 // test variable3
	V4       float32 // test variable4
}

Status of third AHRS filter if available. This is for ANU research group (Ali and Sean)

func (*Ahrs3) MsgID

func (self *Ahrs3) MsgID() uint8

func (*Ahrs3) MsgName

func (self *Ahrs3) MsgName() string

func (*Ahrs3) Pack

func (self *Ahrs3) Pack(p *Packet) error

func (*Ahrs3) Unpack

func (self *Ahrs3) Unpack(p *Packet) error

type AirspeedAutocal

type AirspeedAutocal struct {
	Vx           float32 // GPS velocity north m/s
	Vy           float32 // GPS velocity east m/s
	Vz           float32 // GPS velocity down m/s
	DiffPressure float32 // Differential pressure pascals
	Eas2tas      float32 // Estimated to true airspeed ratio
	Ratio        float32 // Airspeed ratio
	StateX       float32 // EKF state x
	StateY       float32 // EKF state y
	StateZ       float32 // EKF state z
	Pax          float32 // EKF Pax
	Pby          float32 // EKF Pby
	Pcz          float32 // EKF Pcz
}

Airspeed auto-calibration

func (*AirspeedAutocal) MsgID

func (self *AirspeedAutocal) MsgID() uint8

func (*AirspeedAutocal) MsgName

func (self *AirspeedAutocal) MsgName() string

func (*AirspeedAutocal) Pack

func (self *AirspeedAutocal) Pack(p *Packet) error

func (*AirspeedAutocal) Unpack

func (self *AirspeedAutocal) Unpack(p *Packet) error

type Airspeeds

type Airspeeds struct {
	TimeBootMs         uint32 // Timestamp (milliseconds since system boot)
	AirspeedImu        int16  // Airspeed estimate from IMU, cm/s
	AirspeedPitot      int16  // Pitot measured forward airpseed, cm/s
	AirspeedHotWire    int16  // Hot wire anenometer measured airspeed, cm/s
	AirspeedUltrasonic int16  // Ultrasonic measured airspeed, cm/s
	Aoa                int16  // Angle of attack sensor, degrees * 10
	Aoy                int16  // Yaw angle sensor, degrees * 10
}

The airspeed measured by sensors and IMU

func (*Airspeeds) MsgID

func (self *Airspeeds) MsgID() uint8

func (*Airspeeds) MsgName

func (self *Airspeeds) MsgName() string

func (*Airspeeds) Pack

func (self *Airspeeds) Pack(p *Packet) error

func (*Airspeeds) Unpack

func (self *Airspeeds) Unpack(p *Packet) error

type Altitude

type Altitude struct {
	AltitudeMonotonic float32 // This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
	AltitudeAmsl      float32 // This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output AMSL by default and not the WGS84 altitude.
	AltitudeLocal     float32 // This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
	AltitudeRelative  float32 // This is the altitude above the home position. It resets on each change of the current home position.
	AltitudeTerrain   float32 // This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
	BottomClearance   float32 // This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
}

The current system altitude.

func (*Altitude) MsgID

func (self *Altitude) MsgID() uint8

func (*Altitude) MsgName

func (self *Altitude) MsgName() string

func (*Altitude) Pack

func (self *Altitude) Pack(p *Packet) error

func (*Altitude) Unpack

func (self *Altitude) Unpack(p *Packet) error

type Altitudes

type Altitudes struct {
	TimeBootMs     uint32 // Timestamp (milliseconds since system boot)
	AltGps         int32  // GPS altitude in meters, expressed as * 1000 (millimeters), above MSL
	AltImu         int32  // IMU altitude above ground in meters, expressed as * 1000 (millimeters)
	AltBarometric  int32  // barometeric altitude above ground in meters, expressed as * 1000 (millimeters)
	AltOpticalFlow int32  // Optical flow altitude above ground in meters, expressed as * 1000 (millimeters)
	AltRangeFinder int32  // Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters)
	AltExtra       int32  // Extra altitude above ground in meters, expressed as * 1000 (millimeters)
}

The altitude measured by sensors and IMU

func (*Altitudes) MsgID

func (self *Altitudes) MsgID() uint8

func (*Altitudes) MsgName

func (self *Altitudes) MsgName() string

func (*Altitudes) Pack

func (self *Altitudes) Pack(p *Packet) error

func (*Altitudes) Unpack

func (self *Altitudes) Unpack(p *Packet) error

type ApAdc

type ApAdc struct {
	Adc1 uint16 // ADC output 1
	Adc2 uint16 // ADC output 2
	Adc3 uint16 // ADC output 3
	Adc4 uint16 // ADC output 4
	Adc5 uint16 // ADC output 5
	Adc6 uint16 // ADC output 6
}

raw ADC output

func (*ApAdc) MsgID

func (self *ApAdc) MsgID() uint8

func (*ApAdc) MsgName

func (self *ApAdc) MsgName() string

func (*ApAdc) Pack

func (self *ApAdc) Pack(p *Packet) error

func (*ApAdc) Unpack

func (self *ApAdc) Unpack(p *Packet) error

type AslObctrl

type AslObctrl struct {
	Timestamp    uint64  //  Time since system start [us]
	Uelev        float32 //  Elevator command [~]
	Uthrot       float32 //  Throttle command [~]
	Uthrot2      float32 //  Throttle 2 command [~]
	Uaill        float32 //  Left aileron command [~]
	Uailr        float32 //  Right aileron command [~]
	Urud         float32 //  Rudder command [~]
	ObctrlStatus uint8   //  Off-board computer status
}

Off-board controls/commands for ASLUAVs

func (*AslObctrl) MsgID

func (self *AslObctrl) MsgID() uint8

func (*AslObctrl) MsgName

func (self *AslObctrl) MsgName() string

func (*AslObctrl) Pack

func (self *AslObctrl) Pack(p *Packet) error

func (*AslObctrl) Unpack

func (self *AslObctrl) Unpack(p *Packet) error

type AslctrlData

type AslctrlData struct {
	Timestamp       uint64  //  Timestamp
	H               float32 //  See sourcecode for a description of these values...
	Href            float32 //
	HrefT           float32 //
	Pitchangle      float32 // Pitch angle [deg]
	Pitchangleref   float32 // Pitch angle reference[deg]
	Q               float32 //
	Qref            float32 //
	Uelev           float32 //
	Uthrot          float32 //
	Uthrot2         float32 //
	Az              float32 //
	Airspeedref     float32 // Airspeed reference [m/s]
	Yawangle        float32 // Yaw angle [deg]
	Yawangleref     float32 // Yaw angle reference[deg]
	Rollangle       float32 // Roll angle [deg]
	Rollangleref    float32 // Roll angle reference[deg]
	P               float32 //
	Pref            float32 //
	R               float32 //
	Rref            float32 //
	Uail            float32 //
	Urud            float32 //
	AslctrlMode     uint8   //  ASLCTRL control-mode (manual, stabilized, auto, etc...)
	Spoilersengaged uint8   //
}

ASL-fixed-wing controller data

func (*AslctrlData) MsgID

func (self *AslctrlData) MsgID() uint8

func (*AslctrlData) MsgName

func (self *AslctrlData) MsgName() string

func (*AslctrlData) Pack

func (self *AslctrlData) Pack(p *Packet) error

func (*AslctrlData) Unpack

func (self *AslctrlData) Unpack(p *Packet) error

type AslctrlDebug

type AslctrlDebug struct {
	I321 uint32  //  Debug data
	F1   float32 //  Debug data
	F2   float32 //  Debug data
	F3   float32 //  Debug data
	F4   float32 //  Debug data
	F5   float32 //  Debug data
	F6   float32 //  Debug data
	F7   float32 //  Debug data
	F8   float32 //  Debug data
	I81  uint8   //  Debug data
	I82  uint8   //  Debug data
}

ASL-fixed-wing controller debug data

func (*AslctrlDebug) MsgID

func (self *AslctrlDebug) MsgID() uint8

func (*AslctrlDebug) MsgName

func (self *AslctrlDebug) MsgName() string

func (*AslctrlDebug) Pack

func (self *AslctrlDebug) Pack(p *Packet) error

func (*AslctrlDebug) Unpack

func (self *AslctrlDebug) Unpack(p *Packet) error

type AsluavStatus

type AsluavStatus struct {
	MotorRpm     float32  //  Motor RPM
	LedStatus    uint8    //  Status of the position-indicator LEDs
	SatcomStatus uint8    //  Status of the IRIDIUM satellite communication system
	ServoStatus  [8]uint8 //  Status vector for up to 8 servos
}

Extended state information for ASLUAVs

func (*AsluavStatus) MsgID

func (self *AsluavStatus) MsgID() uint8

func (*AsluavStatus) MsgName

func (self *AsluavStatus) MsgName() string

func (*AsluavStatus) Pack

func (self *AsluavStatus) Pack(p *Packet) error

func (*AsluavStatus) Unpack

func (self *AsluavStatus) Unpack(p *Packet) error

type AttPosMocap

type AttPosMocap struct {
	TimeUsec uint64     // Timestamp (micros since boot or Unix epoch)
	Q        [4]float32 // Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
	X        float32    // X position in meters (NED)
	Y        float32    // Y position in meters (NED)
	Z        float32    // Z position in meters (NED)
}

Motion capture attitude and position

func (*AttPosMocap) MsgID

func (self *AttPosMocap) MsgID() uint8

func (*AttPosMocap) MsgName

func (self *AttPosMocap) MsgName() string

func (*AttPosMocap) Pack

func (self *AttPosMocap) Pack(p *Packet) error

func (*AttPosMocap) Unpack

func (self *AttPosMocap) Unpack(p *Packet) error

type Attitude

type Attitude struct {
	TimeBootMs uint32  // Timestamp (milliseconds since system boot)
	Roll       float32 // Roll angle (rad, -pi..+pi)
	Pitch      float32 // Pitch angle (rad, -pi..+pi)
	Yaw        float32 // Yaw angle (rad, -pi..+pi)
	Rollspeed  float32 // Roll angular speed (rad/s)
	Pitchspeed float32 // Pitch angular speed (rad/s)
	Yawspeed   float32 // Yaw angular speed (rad/s)
}

The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).

func (*Attitude) MsgID

func (self *Attitude) MsgID() uint8

func (*Attitude) MsgName

func (self *Attitude) MsgName() string

func (*Attitude) Pack

func (self *Attitude) Pack(p *Packet) error

func (*Attitude) Unpack

func (self *Attitude) Unpack(p *Packet) error

type AttitudeControl

type AttitudeControl struct {
	Roll         float32 // roll
	Pitch        float32 // pitch
	Yaw          float32 // yaw
	Thrust       float32 // thrust
	Target       uint8   // The system to be controlled
	RollManual   uint8   // roll control enabled auto:0, manual:1
	PitchManual  uint8   // pitch auto:0, manual:1
	YawManual    uint8   // yaw auto:0, manual:1
	ThrustManual uint8   // thrust auto:0, manual:1
}

func (*AttitudeControl) MsgID

func (self *AttitudeControl) MsgID() uint8

func (*AttitudeControl) MsgName

func (self *AttitudeControl) MsgName() string

func (*AttitudeControl) Pack

func (self *AttitudeControl) Pack(p *Packet) error

func (*AttitudeControl) Unpack

func (self *AttitudeControl) Unpack(p *Packet) error

type AttitudeQuaternion

type AttitudeQuaternion struct {
	TimeBootMs uint32  // Timestamp (milliseconds since system boot)
	Q1         float32 // Quaternion component 1, w (1 in null-rotation)
	Q2         float32 // Quaternion component 2, x (0 in null-rotation)
	Q3         float32 // Quaternion component 3, y (0 in null-rotation)
	Q4         float32 // Quaternion component 4, z (0 in null-rotation)
	Rollspeed  float32 // Roll angular speed (rad/s)
	Pitchspeed float32 // Pitch angular speed (rad/s)
	Yawspeed   float32 // Yaw angular speed (rad/s)
}

The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0).

func (*AttitudeQuaternion) MsgID

func (self *AttitudeQuaternion) MsgID() uint8

func (*AttitudeQuaternion) MsgName

func (self *AttitudeQuaternion) MsgName() string

func (*AttitudeQuaternion) Pack

func (self *AttitudeQuaternion) Pack(p *Packet) error

func (*AttitudeQuaternion) Unpack

func (self *AttitudeQuaternion) Unpack(p *Packet) error

type AttitudeQuaternionCov

type AttitudeQuaternionCov struct {
	TimeBootMs uint32     // Timestamp (milliseconds since system boot)
	Q          [4]float32 // Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
	Rollspeed  float32    // Roll angular speed (rad/s)
	Pitchspeed float32    // Pitch angular speed (rad/s)
	Yawspeed   float32    // Yaw angular speed (rad/s)
	Covariance [9]float32 // Attitude covariance
}

The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0).

func (*AttitudeQuaternionCov) MsgID

func (self *AttitudeQuaternionCov) MsgID() uint8

func (*AttitudeQuaternionCov) MsgName

func (self *AttitudeQuaternionCov) MsgName() string

func (*AttitudeQuaternionCov) Pack

func (self *AttitudeQuaternionCov) Pack(p *Packet) error

func (*AttitudeQuaternionCov) Unpack

func (self *AttitudeQuaternionCov) Unpack(p *Packet) error

type AttitudeTarget

type AttitudeTarget struct {
	TimeBootMs    uint32     // Timestamp in milliseconds since system boot
	Q             [4]float32 // Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
	BodyRollRate  float32    // Body roll rate in radians per second
	BodyPitchRate float32    // Body roll rate in radians per second
	BodyYawRate   float32    // Body roll rate in radians per second
	Thrust        float32    // Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
	TypeMask      uint8      // Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
}

Set the vehicle attitude and body angular rates.

func (*AttitudeTarget) MsgID

func (self *AttitudeTarget) MsgID() uint8

func (*AttitudeTarget) MsgName

func (self *AttitudeTarget) MsgName() string

func (*AttitudeTarget) Pack

func (self *AttitudeTarget) Pack(p *Packet) error

func (*AttitudeTarget) Unpack

func (self *AttitudeTarget) Unpack(p *Packet) error

type AuthKey

type AuthKey struct {
	Key [32]byte // key
}

Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety.

func (*AuthKey) MsgID

func (self *AuthKey) MsgID() uint8

func (*AuthKey) MsgName

func (self *AuthKey) MsgName() string

func (*AuthKey) Pack

func (self *AuthKey) Pack(p *Packet) error

func (*AuthKey) Unpack

func (self *AuthKey) Unpack(p *Packet) error

type AutopilotVersion

type AutopilotVersion struct {
	Capabilities            uint64   // bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
	Uid                     uint64   // UID if provided by hardware
	FlightSwVersion         uint32   // Firmware version number
	MiddlewareSwVersion     uint32   // Middleware version number
	OsSwVersion             uint32   // Operating system version number
	BoardVersion            uint32   // HW / board version (last 8 bytes should be silicon ID, if any)
	VendorId                uint16   // ID of the board vendor
	ProductId               uint16   // ID of the product
	FlightCustomVersion     [8]uint8 // Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
	MiddlewareCustomVersion [8]uint8 // Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
	OsCustomVersion         [8]uint8 // Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
}

Version and capability of autopilot software

func (*AutopilotVersion) MsgID

func (self *AutopilotVersion) MsgID() uint8

func (*AutopilotVersion) MsgName

func (self *AutopilotVersion) MsgName() string

func (*AutopilotVersion) Pack

func (self *AutopilotVersion) Pack(p *Packet) error

func (*AutopilotVersion) Unpack

func (self *AutopilotVersion) Unpack(p *Packet) error

type AutopilotVersionRequest

type AutopilotVersionRequest struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Request the autopilot version from the system/component.

func (*AutopilotVersionRequest) MsgID

func (self *AutopilotVersionRequest) MsgID() uint8

func (*AutopilotVersionRequest) MsgName

func (self *AutopilotVersionRequest) MsgName() string

func (*AutopilotVersionRequest) Pack

func (self *AutopilotVersionRequest) Pack(p *Packet) error

func (*AutopilotVersionRequest) Unpack

func (self *AutopilotVersionRequest) Unpack(p *Packet) error

type Battery2

type Battery2 struct {
	Voltage        uint16 // voltage in millivolts
	CurrentBattery int16  // Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
}

2nd Battery status

func (*Battery2) MsgID

func (self *Battery2) MsgID() uint8

func (*Battery2) MsgName

func (self *Battery2) MsgName() string

func (*Battery2) Pack

func (self *Battery2) Pack(p *Packet) error

func (*Battery2) Unpack

func (self *Battery2) Unpack(p *Packet) error

type BatteryStatus

type BatteryStatus struct {
	CurrentConsumed  int32      // Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
	EnergyConsumed   int32      // Consumed energy, in 100*Joules (intergrated U*I*dt)  (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
	Temperature      int16      // Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
	Voltages         [10]uint16 // Battery voltage of cells, in millivolts (1 = 1 millivolt)
	CurrentBattery   int16      // Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
	Id               uint8      // Battery ID
	BatteryFunction  uint8      // Function of the battery
	Type             uint8      // Type (chemistry) of the battery
	BatteryRemaining int8       // Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
}

Battery information

func (*BatteryStatus) MsgID

func (self *BatteryStatus) MsgID() uint8

func (*BatteryStatus) MsgName

func (self *BatteryStatus) MsgName() string

func (*BatteryStatus) Pack

func (self *BatteryStatus) Pack(p *Packet) error

func (*BatteryStatus) Unpack

func (self *BatteryStatus) Unpack(p *Packet) error

type BriefFeature

type BriefFeature struct {
	X                     float32   // x position in m
	Y                     float32   // y position in m
	Z                     float32   // z position in m
	Response              float32   // Harris operator response at this location
	Size                  uint16    // Size in pixels
	Orientation           uint16    // Orientation
	OrientationAssignment uint8     // Orientation assignment 0: false, 1:true
	Descriptor            [32]uint8 // Descriptor
}

func (*BriefFeature) MsgID

func (self *BriefFeature) MsgID() uint8

func (*BriefFeature) MsgName

func (self *BriefFeature) MsgName() string

func (*BriefFeature) Pack

func (self *BriefFeature) Pack(p *Packet) error

func (*BriefFeature) Unpack

func (self *BriefFeature) Unpack(p *Packet) error

type CameraFeedback

type CameraFeedback struct {
	TimeUsec     uint64  // Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB)
	Lat          int32   // Latitude in (deg * 1E7)
	Lng          int32   // Longitude in (deg * 1E7)
	AltMsl       float32 // Altitude Absolute (meters AMSL)
	AltRel       float32 // Altitude Relative (meters above HOME location)
	Roll         float32 // Camera Roll angle (earth frame, degrees, +-180)
	Pitch        float32 // Camera Pitch angle (earth frame, degrees, +-180)
	Yaw          float32 // Camera Yaw (earth frame, degrees, 0-360, true)
	FocLen       float32 // Focal Length (mm)
	ImgIdx       uint16  // Image index
	TargetSystem uint8   // System ID
	CamIdx       uint8   // Camera ID
	Flags        uint8   // See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask
}

Camera Capture Feedback

func (*CameraFeedback) MsgID

func (self *CameraFeedback) MsgID() uint8

func (*CameraFeedback) MsgName

func (self *CameraFeedback) MsgName() string

func (*CameraFeedback) Pack

func (self *CameraFeedback) Pack(p *Packet) error

func (*CameraFeedback) Unpack

func (self *CameraFeedback) Unpack(p *Packet) error

type CameraStatus

type CameraStatus struct {
	TimeUsec     uint64  // Image timestamp (microseconds since UNIX epoch, according to camera clock)
	P1           float32 // Parameter 1 (meaning depends on event, see CAMERA_STATUS_TYPES enum)
	P2           float32 // Parameter 2 (meaning depends on event, see CAMERA_STATUS_TYPES enum)
	P3           float32 // Parameter 3 (meaning depends on event, see CAMERA_STATUS_TYPES enum)
	P4           float32 // Parameter 4 (meaning depends on event, see CAMERA_STATUS_TYPES enum)
	ImgIdx       uint16  // Image index
	TargetSystem uint8   // System ID
	CamIdx       uint8   // Camera ID
	EventId      uint8   // See CAMERA_STATUS_TYPES enum for definition of the bitmask
}

Camera Event

func (*CameraStatus) MsgID

func (self *CameraStatus) MsgID() uint8

func (*CameraStatus) MsgName

func (self *CameraStatus) MsgName() string

func (*CameraStatus) Pack

func (self *CameraStatus) Pack(p *Packet) error

func (*CameraStatus) Unpack

func (self *CameraStatus) Unpack(p *Packet) error

type CameraTrigger

type CameraTrigger struct {
	TimeUsec uint64 // Timestamp for the image frame in microseconds
	Seq      uint32 // Image frame sequence
}

Camera-IMU triggering and synchronisation message.

func (*CameraTrigger) MsgID

func (self *CameraTrigger) MsgID() uint8

func (*CameraTrigger) MsgName

func (self *CameraTrigger) MsgName() string

func (*CameraTrigger) Pack

func (self *CameraTrigger) Pack(p *Packet) error

func (*CameraTrigger) Unpack

func (self *CameraTrigger) Unpack(p *Packet) error

type ChangeOperatorControl

type ChangeOperatorControl struct {
	TargetSystem   uint8    // System the GCS requests control for
	ControlRequest uint8    // 0: request control of this MAV, 1: Release control of this MAV
	Version        uint8    // 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
	Passkey        [25]byte // Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
}

Request to control this MAV

func (*ChangeOperatorControl) MsgID

func (self *ChangeOperatorControl) MsgID() uint8

func (*ChangeOperatorControl) MsgName

func (self *ChangeOperatorControl) MsgName() string

func (*ChangeOperatorControl) Pack

func (self *ChangeOperatorControl) Pack(p *Packet) error

func (*ChangeOperatorControl) Unpack

func (self *ChangeOperatorControl) Unpack(p *Packet) error

type ChangeOperatorControlAck

type ChangeOperatorControlAck struct {
	GcsSystemId    uint8 // ID of the GCS this message
	ControlRequest uint8 // 0: request control of this MAV, 1: Release control of this MAV
	Ack            uint8 // 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
}

Accept / deny control of this MAV

func (*ChangeOperatorControlAck) MsgID

func (self *ChangeOperatorControlAck) MsgID() uint8

func (*ChangeOperatorControlAck) MsgName

func (self *ChangeOperatorControlAck) MsgName() string

func (*ChangeOperatorControlAck) Pack

func (self *ChangeOperatorControlAck) Pack(p *Packet) error

func (*ChangeOperatorControlAck) Unpack

func (self *ChangeOperatorControlAck) Unpack(p *Packet) error

type CommandAck

type CommandAck struct {
	Command uint16 // Command ID, as defined by MAV_CMD enum.
	Result  uint8  // See MAV_RESULT enum
}

Report status of a command. Includes feedback wether the command was executed.

func (*CommandAck) MsgID

func (self *CommandAck) MsgID() uint8

func (*CommandAck) MsgName

func (self *CommandAck) MsgName() string

func (*CommandAck) Pack

func (self *CommandAck) Pack(p *Packet) error

func (*CommandAck) Unpack

func (self *CommandAck) Unpack(p *Packet) error

type CommandInt

type CommandInt struct {
	Param1          float32 // PARAM1, see MAV_CMD enum
	Param2          float32 // PARAM2, see MAV_CMD enum
	Param3          float32 // PARAM3, see MAV_CMD enum
	Param4          float32 // PARAM4, see MAV_CMD enum
	X               int32   // PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
	Y               int32   // PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
	Z               float32 // PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
	Command         uint16  // The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
	Frame           uint8   // The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
	Current         uint8   // false:0, true:1
	Autocontinue    uint8   // autocontinue to next wp
}

Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value.

func (*CommandInt) MsgID

func (self *CommandInt) MsgID() uint8

func (*CommandInt) MsgName

func (self *CommandInt) MsgName() string

func (*CommandInt) Pack

func (self *CommandInt) Pack(p *Packet) error

func (*CommandInt) Unpack

func (self *CommandInt) Unpack(p *Packet) error

type CommandLong

type CommandLong struct {
	Param1          float32 // Parameter 1, as defined by MAV_CMD enum.
	Param2          float32 // Parameter 2, as defined by MAV_CMD enum.
	Param3          float32 // Parameter 3, as defined by MAV_CMD enum.
	Param4          float32 // Parameter 4, as defined by MAV_CMD enum.
	Param5          float32 // Parameter 5, as defined by MAV_CMD enum.
	Param6          float32 // Parameter 6, as defined by MAV_CMD enum.
	Param7          float32 // Parameter 7, as defined by MAV_CMD enum.
	Command         uint16  // Command ID, as defined by MAV_CMD enum.
	TargetSystem    uint8   // System which should execute the command
	TargetComponent uint8   // Component which should execute the command, 0 for all components
	Confirmation    uint8   // 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
}

Send a command with up to seven parameters to the MAV

func (*CommandLong) MsgID

func (self *CommandLong) MsgID() uint8

func (*CommandLong) MsgName

func (self *CommandLong) MsgName() string

func (*CommandLong) Pack

func (self *CommandLong) Pack(p *Packet) error

func (*CommandLong) Unpack

func (self *CommandLong) Unpack(p *Packet) error

type CompassmotStatus

type CompassmotStatus struct {
	Current       float32 // current (amps)
	Compensationx float32 // Motor Compensation X
	Compensationy float32 // Motor Compensation Y
	Compensationz float32 // Motor Compensation Z
	Throttle      uint16  // throttle (percent*10)
	Interference  uint16  // interference (percent)
}

Status of compassmot calibration

func (*CompassmotStatus) MsgID

func (self *CompassmotStatus) MsgID() uint8

func (*CompassmotStatus) MsgName

func (self *CompassmotStatus) MsgName() string

func (*CompassmotStatus) Pack

func (self *CompassmotStatus) Pack(p *Packet) error

func (*CompassmotStatus) Unpack

func (self *CompassmotStatus) Unpack(p *Packet) error

type ControlSystemState

type ControlSystemState struct {
	TimeUsec    uint64     // Timestamp (micros since boot or Unix epoch)
	XAcc        float32    // X acceleration in body frame
	YAcc        float32    // Y acceleration in body frame
	ZAcc        float32    // Z acceleration in body frame
	XVel        float32    // X velocity in body frame
	YVel        float32    // Y velocity in body frame
	ZVel        float32    // Z velocity in body frame
	XPos        float32    // X position in local frame
	YPos        float32    // Y position in local frame
	ZPos        float32    // Z position in local frame
	Airspeed    float32    // Airspeed, set to -1 if unknown
	VelVariance [3]float32 // Variance of body velocity estimate
	PosVariance [3]float32 // Variance in local position
	Q           [4]float32 // The attitude, represented as Quaternion
	RollRate    float32    // Angular rate in roll axis
	PitchRate   float32    // Angular rate in pitch axis
	YawRate     float32    // Angular rate in yaw axis
}

The smoothed, monotonic system state used to feed the control loops of the system.

func (*ControlSystemState) MsgID

func (self *ControlSystemState) MsgID() uint8

func (*ControlSystemState) MsgName

func (self *ControlSystemState) MsgName() string

func (*ControlSystemState) Pack

func (self *ControlSystemState) Pack(p *Packet) error

func (*ControlSystemState) Unpack

func (self *ControlSystemState) Unpack(p *Packet) error

type Data16

type Data16 struct {
	Type uint8     // data type
	Len  uint8     // data length
	Data [16]uint8 // raw data
}

Data packet, size 16

func (*Data16) MsgID

func (self *Data16) MsgID() uint8

func (*Data16) MsgName

func (self *Data16) MsgName() string

func (*Data16) Pack

func (self *Data16) Pack(p *Packet) error

func (*Data16) Unpack

func (self *Data16) Unpack(p *Packet) error

type Data32

type Data32 struct {
	Type uint8     // data type
	Len  uint8     // data length
	Data [32]uint8 // raw data
}

Data packet, size 32

func (*Data32) MsgID

func (self *Data32) MsgID() uint8

func (*Data32) MsgName

func (self *Data32) MsgName() string

func (*Data32) Pack

func (self *Data32) Pack(p *Packet) error

func (*Data32) Unpack

func (self *Data32) Unpack(p *Packet) error

type Data64

type Data64 struct {
	Type uint8     // data type
	Len  uint8     // data length
	Data [64]uint8 // raw data
}

Data packet, size 64

func (*Data64) MsgID

func (self *Data64) MsgID() uint8

func (*Data64) MsgName

func (self *Data64) MsgName() string

func (*Data64) Pack

func (self *Data64) Pack(p *Packet) error

func (*Data64) Unpack

func (self *Data64) Unpack(p *Packet) error

type Data96

type Data96 struct {
	Type uint8     // data type
	Len  uint8     // data length
	Data [96]uint8 // raw data
}

Data packet, size 96

func (*Data96) MsgID

func (self *Data96) MsgID() uint8

func (*Data96) MsgName

func (self *Data96) MsgName() string

func (*Data96) Pack

func (self *Data96) Pack(p *Packet) error

func (*Data96) Unpack

func (self *Data96) Unpack(p *Packet) error

type DataStream

type DataStream struct {
	MessageRate uint16 // The message rate
	StreamId    uint8  // The ID of the requested data stream
	OnOff       uint8  // 1 stream is enabled, 0 stream is stopped.
}

THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD.

func (*DataStream) MsgID

func (self *DataStream) MsgID() uint8

func (*DataStream) MsgName

func (self *DataStream) MsgName() string

func (*DataStream) Pack

func (self *DataStream) Pack(p *Packet) error

func (*DataStream) Unpack

func (self *DataStream) Unpack(p *Packet) error

type DataTransmissionHandshake

type DataTransmissionHandshake struct {
	Size       uint32 // total data size in bytes (set on ACK only)
	Width      uint16 // Width of a matrix or image
	Height     uint16 // Height of a matrix or image
	Packets    uint16 // number of packets beeing sent (set on ACK only)
	Type       uint8  // type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
	Payload    uint8  // payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
	JpgQuality uint8  // JPEG quality out of [1,100]
}

func (*DataTransmissionHandshake) MsgID

func (self *DataTransmissionHandshake) MsgID() uint8

func (*DataTransmissionHandshake) MsgName

func (self *DataTransmissionHandshake) MsgName() string

func (*DataTransmissionHandshake) Pack

func (self *DataTransmissionHandshake) Pack(p *Packet) error

func (*DataTransmissionHandshake) Unpack

func (self *DataTransmissionHandshake) Unpack(p *Packet) error

type Debug

type Debug struct {
	TimeBootMs uint32  // Timestamp (milliseconds since system boot)
	Value      float32 // DEBUG value
	Ind        uint8   // index of debug variable
}

Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N.

func (*Debug) MsgID

func (self *Debug) MsgID() uint8

func (*Debug) MsgName

func (self *Debug) MsgName() string

func (*Debug) Pack

func (self *Debug) Pack(p *Packet) error

func (*Debug) Unpack

func (self *Debug) Unpack(p *Packet) error

type DebugVect

type DebugVect struct {
	TimeUsec uint64   // Timestamp
	X        float32  // x
	Y        float32  // y
	Z        float32  // z
	Name     [10]byte // Name
}

func (*DebugVect) MsgID

func (self *DebugVect) MsgID() uint8

func (*DebugVect) MsgName

func (self *DebugVect) MsgName() string

func (*DebugVect) Pack

func (self *DebugVect) Pack(p *Packet) error

func (*DebugVect) Unpack

func (self *DebugVect) Unpack(p *Packet) error

type Decoder

type Decoder struct {
	CurrSeqID uint8        // last seq id decoded
	Dialects  DialectSlice // dialects that can be decoded
	// contains filtered or unexported fields
}

func NewDecoder

func NewDecoder(r io.Reader) *Decoder

func (*Decoder) Decode

func (dec *Decoder) Decode() (*Packet, error)

Decoder reads and parses from its reader Typically, the caller will check the p.MsgID to see if it's a message they're interested in, and convert it to the corresponding type via Message.FromPacket()

func (*Decoder) DecodeBytes

func (dec *Decoder) DecodeBytes(b []byte) (*Packet, error)

Decode a packet from a previously received buffer (such as a UDP packet), b must contain a complete message

type DetectionStats

type DetectionStats struct {
	Detections        uint32  // Number of detections
	ClusterIters      uint32  // Number of cluster iterations
	BestScore         float32 // Best score
	BestLat           int32   // Latitude of the best detection * 1E7
	BestLon           int32   // Longitude of the best detection * 1E7
	BestAlt           int32   // Altitude of the best detection * 1E3
	BestDetectionId   uint32  // Best detection ID
	BestClusterId     uint32  // Best cluster ID
	BestClusterIterId uint32  // Best cluster ID
	ImagesDone        uint32  // Number of images already processed
	ImagesTodo        uint32  // Number of images still to process
	Fps               float32 // Average images per seconds processed
}

func (*DetectionStats) MsgID

func (self *DetectionStats) MsgID() uint8

func (*DetectionStats) MsgName

func (self *DetectionStats) MsgName() string

func (*DetectionStats) Pack

func (self *DetectionStats) Pack(p *Packet) error

func (*DetectionStats) Unpack

func (self *DetectionStats) Unpack(p *Packet) error

type Dialect

type Dialect struct {
	Name string
	// contains filtered or unexported fields
}

Dialect represents a set of message definitions. Some dialects have conflicting definitions for given message IDs, so a list of dialects must be provided to an Encoder/Decoder in order to specify which packets to use for the conflicting IDs.

The 'DialectCommon' dialect is added to all Encoders/Decoders by default.

var DialectArdupilotmega *Dialect = &Dialect{
	Name: "ardupilotmega",
	crcExtras: map[uint8]uint8{
		150: 134,
		151: 219,
		152: 208,
		153: 188,
		154: 84,
		155: 22,
		156: 19,
		157: 21,
		158: 134,
		160: 78,
		161: 68,
		162: 189,
		163: 127,
		164: 154,
		165: 21,
		166: 21,
		167: 144,
		168: 1,
		169: 234,
		170: 73,
		171: 181,
		172: 22,
		173: 83,
		174: 167,
		175: 138,
		176: 234,
		177: 240,
		178: 47,
		179: 189,
		180: 52,
		181: 174,
		182: 229,
		183: 85,
		186: 72,
		191: 92,
		192: 36,
		193: 71,
		194: 98,
		200: 134,
		201: 205,
		202: 94,
		203: 128,
		204: 54,
		205: 63,
		206: 112,
		207: 201,
		208: 221,
		209: 226,
		210: 238,
		215: 241,
		216: 155,
		217: 43,
		218: 149,
		226: 207,
	},
}

DialectArdupilotmega is the dialect represented by ardupilotmega.xml

var DialectAsluav *Dialect = &Dialect{
	Name: "ASLUAV",
	crcExtras: map[uint8]uint8{
		201: 218,
		202: 231,
		203: 0,
		204: 251,
		205: 97,
		206: 64,
		207: 234,
		208: 175,
		209: 62,
		210: 129,
		211: 54,
	},
}

DialectAsluav is the dialect represented by ASLUAV.xml

var DialectCommon *Dialect = &Dialect{
	Name: "common",
	crcExtras: map[uint8]uint8{
		0:   50,
		1:   124,
		2:   137,
		4:   237,
		5:   217,
		6:   104,
		7:   119,
		11:  89,
		20:  214,
		21:  159,
		22:  220,
		23:  168,
		24:  24,
		25:  23,
		26:  170,
		27:  144,
		28:  67,
		29:  115,
		30:  39,
		31:  246,
		32:  185,
		33:  104,
		34:  237,
		35:  244,
		36:  222,
		37:  212,
		38:  9,
		39:  254,
		40:  230,
		41:  28,
		42:  28,
		43:  132,
		44:  221,
		45:  232,
		46:  11,
		47:  153,
		48:  41,
		49:  39,
		50:  78,
		54:  15,
		55:  3,
		61:  153,
		62:  183,
		63:  51,
		64:  59,
		65:  118,
		66:  148,
		67:  21,
		69:  243,
		70:  124,
		73:  38,
		74:  20,
		75:  158,
		76:  152,
		77:  143,
		81:  106,
		82:  49,
		83:  22,
		84:  143,
		85:  140,
		86:  5,
		87:  150,
		89:  231,
		90:  183,
		91:  63,
		92:  54,
		100: 175,
		101: 102,
		102: 158,
		103: 208,
		104: 56,
		105: 93,
		106: 138,
		107: 108,
		108: 32,
		109: 185,
		110: 84,
		111: 34,
		112: 174,
		113: 124,
		114: 237,
		115: 4,
		116: 76,
		117: 128,
		118: 56,
		119: 116,
		120: 134,
		121: 237,
		122: 203,
		123: 250,
		124: 87,
		125: 203,
		126: 220,
		127: 25,
		128: 226,
		129: 46,
		130: 29,
		131: 223,
		132: 85,
		133: 6,
		134: 229,
		135: 203,
		136: 1,
		137: 195,
		138: 109,
		139: 168,
		140: 181,
		141: 148,
		142: 72,
		143: 131,
		146: 103,
		147: 154,
		148: 178,
		149: 200,
		241: 90,
		242: 104,
		243: 85,
		244: 95,
		245: 130,
		246: 92,
		248: 8,
		249: 204,
		250: 49,
		251: 170,
		252: 44,
		253: 83,
		254: 46,
	},
}

DialectCommon is the dialect represented by common.xml

var DialectMatrixpilot *Dialect = &Dialect{
	Name: "matrixpilot",
	crcExtras: map[uint8]uint8{
		150: 181,
		151: 26,
		152: 101,
		153: 109,
		155: 12,
		156: 218,
		157: 133,
		158: 208,
		170: 150,
		171: 169,
		172: 191,
		173: 121,
		174: 54,
		175: 171,
		176: 142,
		177: 249,
		178: 123,
		179: 7,
		180: 222,
		181: 55,
		182: 154,
	},
}

DialectMatrixpilot is the dialect represented by matrixpilot.xml

var DialectPixhawk *Dialect = &Dialect{
	Name: "pixhawk",
	crcExtras: map[uint8]uint8{
		151: 108,
		152: 86,
		153: 95,
		154: 224,
		160: 22,
		170: 28,
		171: 249,
		172: 182,
		180: 153,
		181: 16,
		182: 29,
		183: 162,
		190: 90,
		191: 95,
		192: 36,
		195: 88,
		200: 254,
		205: 87,
		206: 19,
	},
}

DialectPixhawk is the dialect represented by pixhawk.xml

var DialectUalberta *Dialect = &Dialect{
	Name: "ualberta",
	crcExtras: map[uint8]uint8{
		220: 34,
		221: 71,
		222: 15,
	},
}

DialectUalberta is the dialect represented by ualberta.xml

type DialectSlice

type DialectSlice []*Dialect

Alias for a slice of Dialect pointers Only really intended to be accessed as a field on Encoder/Decoder

func (*DialectSlice) Add

func (ds *DialectSlice) Add(d *Dialect)

Add appends d if not already present in ds

func (*DialectSlice) IndexOf

func (ds *DialectSlice) IndexOf(d *Dialect) int

IndexOf returns the index of d or -1 if not found

func (*DialectSlice) Remove

func (ds *DialectSlice) Remove(d *Dialect)

Remove removes d if present in ds

type DigicamConfigure

type DigicamConfigure struct {
	ExtraValue      float32 // Correspondent value to given extra_param
	ShutterSpeed    uint16  // Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
	Mode            uint8   // Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
	Aperture        uint8   // F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
	Iso             uint8   // ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
	ExposureType    uint8   // Exposure type enumeration from 1 to N (0 means ignore)
	CommandId       uint8   // Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
	EngineCutOff    uint8   // Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
	ExtraParam      uint8   // Extra parameters enumeration (0 means ignore)
}

Configure on-board Camera Control System.

func (*DigicamConfigure) MsgID

func (self *DigicamConfigure) MsgID() uint8

func (*DigicamConfigure) MsgName

func (self *DigicamConfigure) MsgName() string

func (*DigicamConfigure) Pack

func (self *DigicamConfigure) Pack(p *Packet) error

func (*DigicamConfigure) Unpack

func (self *DigicamConfigure) Unpack(p *Packet) error

type DigicamControl

type DigicamControl struct {
	ExtraValue      float32 // Correspondent value to given extra_param
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
	Session         uint8   // 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
	ZoomPos         uint8   // 1 to N //Zoom's absolute position (0 means ignore)
	ZoomStep        int8    // -100 to 100 //Zooming step value to offset zoom from the current position
	FocusLock       uint8   // 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
	Shot            uint8   // 0: ignore, 1: shot or start filming
	CommandId       uint8   // Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
	ExtraParam      uint8   // Extra parameters enumeration (0 means ignore)
}

Control on-board Camera Control System to take shots.

func (*DigicamControl) MsgID

func (self *DigicamControl) MsgID() uint8

func (*DigicamControl) MsgName

func (self *DigicamControl) MsgName() string

func (*DigicamControl) Pack

func (self *DigicamControl) Pack(p *Packet) error

func (*DigicamControl) Unpack

func (self *DigicamControl) Unpack(p *Packet) error

type DistanceSensor

type DistanceSensor struct {
	TimeBootMs      uint32 // Time since system boot
	MinDistance     uint16 // Minimum distance the sensor can measure in centimeters
	MaxDistance     uint16 // Maximum distance the sensor can measure in centimeters
	CurrentDistance uint16 // Current distance reading
	Type            uint8  // Type from MAV_DISTANCE_SENSOR enum.
	Id              uint8  // Onboard ID of the sensor
	Orientation     uint8  // Direction the sensor faces from MAV_SENSOR_ORIENTATION enum.
	Covariance      uint8  // Measurement covariance in centimeters, 0 for unknown / invalid readings
}

func (*DistanceSensor) MsgID

func (self *DistanceSensor) MsgID() uint8

func (*DistanceSensor) MsgName

func (self *DistanceSensor) MsgName() string

func (*DistanceSensor) Pack

func (self *DistanceSensor) Pack(p *Packet) error

func (*DistanceSensor) Unpack

func (self *DistanceSensor) Unpack(p *Packet) error

type EkfExt

type EkfExt struct {
	Timestamp uint64  //  Time since system start [us]
	Windspeed float32 //  Magnitude of wind velocity (in lateral inertial plane) [m/s]
	Winddir   float32 //  Wind heading angle from North [rad]
	Windz     float32 //  Z (Down) component of inertial wind velocity [m/s]
	Airspeed  float32 //  Magnitude of air velocity [m/s]
	Beta      float32 //  Sideslip angle [rad]
	Alpha     float32 //  Angle of attack [rad]
}

Extended EKF state estimates for ASLUAVs

func (*EkfExt) MsgID

func (self *EkfExt) MsgID() uint8

func (*EkfExt) MsgName

func (self *EkfExt) MsgName() string

func (*EkfExt) Pack

func (self *EkfExt) Pack(p *Packet) error

func (*EkfExt) Unpack

func (self *EkfExt) Unpack(p *Packet) error

type EkfStatusReport

type EkfStatusReport struct {
	VelocityVariance   float32 // Velocity variance
	PosHorizVariance   float32 // Horizontal Position variance
	PosVertVariance    float32 // Vertical Position variance
	CompassVariance    float32 // Compass variance
	TerrainAltVariance float32 // Terrain Altitude variance
	Flags              uint16  // Flags
}

EKF Status message including flags and variances

func (*EkfStatusReport) MsgID

func (self *EkfStatusReport) MsgID() uint8

func (*EkfStatusReport) MsgName

func (self *EkfStatusReport) MsgName() string

func (*EkfStatusReport) Pack

func (self *EkfStatusReport) Pack(p *Packet) error

func (*EkfStatusReport) Unpack

func (self *EkfStatusReport) Unpack(p *Packet) error

type EncapsulatedData

type EncapsulatedData struct {
	Seqnr uint16     // sequence number (starting with 0 on every transmission)
	Data  [253]uint8 // image data bytes
}

func (*EncapsulatedData) MsgID

func (self *EncapsulatedData) MsgID() uint8

func (*EncapsulatedData) MsgName

func (self *EncapsulatedData) MsgName() string

func (*EncapsulatedData) Pack

func (self *EncapsulatedData) Pack(p *Packet) error

func (*EncapsulatedData) Unpack

func (self *EncapsulatedData) Unpack(p *Packet) error

type Encoder

type Encoder struct {
	CurrSeqID uint8        // last seq id encoded
	Dialects  DialectSlice // dialects that can be encoded
	// contains filtered or unexported fields
}

func NewEncoder

func NewEncoder(w io.Writer) *Encoder

func (*Encoder) Encode

func (enc *Encoder) Encode(sysID, compID uint8, m Message) error

helper that accepts a Message, internally converts it to a Packet, sets the Packet's SeqID based on the and then writes it to its writer via EncodePacket()

func (*Encoder) EncodePacket

func (enc *Encoder) EncodePacket(p *Packet) error

Encode writes p to its writer

type ExtendedSysState

type ExtendedSysState struct {
	VtolState   uint8 // The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.
	LandedState uint8 // The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
}

Provides state for additional features

func (*ExtendedSysState) MsgID

func (self *ExtendedSysState) MsgID() uint8

func (*ExtendedSysState) MsgName

func (self *ExtendedSysState) MsgName() string

func (*ExtendedSysState) Pack

func (self *ExtendedSysState) Pack(p *Packet) error

func (*ExtendedSysState) Unpack

func (self *ExtendedSysState) Unpack(p *Packet) error

type FenceFetchPoint

type FenceFetchPoint struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
	Idx             uint8 // point index (first point is 1, 0 is for return point)
}

Request a current fence point from MAV

func (*FenceFetchPoint) MsgID

func (self *FenceFetchPoint) MsgID() uint8

func (*FenceFetchPoint) MsgName

func (self *FenceFetchPoint) MsgName() string

func (*FenceFetchPoint) Pack

func (self *FenceFetchPoint) Pack(p *Packet) error

func (*FenceFetchPoint) Unpack

func (self *FenceFetchPoint) Unpack(p *Packet) error

type FencePoint

type FencePoint struct {
	Lat             float32 // Latitude of point
	Lng             float32 // Longitude of point
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
	Idx             uint8   // point index (first point is 1, 0 is for return point)
	Count           uint8   // total number of points (for sanity checking)
}

A fence point. Used to set a point when from

GCS -> MAV. Also used to return a point from MAV -> GCS

func (*FencePoint) MsgID

func (self *FencePoint) MsgID() uint8

func (*FencePoint) MsgName

func (self *FencePoint) MsgName() string

func (*FencePoint) Pack

func (self *FencePoint) Pack(p *Packet) error

func (*FencePoint) Unpack

func (self *FencePoint) Unpack(p *Packet) error

type FenceStatus

type FenceStatus struct {
	BreachTime   uint32 // time of last breach in milliseconds since boot
	BreachCount  uint16 // number of fence breaches
	BreachStatus uint8  // 0 if currently inside fence, 1 if outside
	BreachType   uint8  // last breach type (see FENCE_BREACH_* enum)
}

Status of geo-fencing. Sent in extended

status stream when fencing enabled

func (*FenceStatus) MsgID

func (self *FenceStatus) MsgID() uint8

func (*FenceStatus) MsgName

func (self *FenceStatus) MsgName() string

func (*FenceStatus) Pack

func (self *FenceStatus) Pack(p *Packet) error

func (*FenceStatus) Unpack

func (self *FenceStatus) Unpack(p *Packet) error

type FileTransferProtocol

type FileTransferProtocol struct {
	TargetNetwork   uint8      // Network ID (0 for broadcast)
	TargetSystem    uint8      // System ID (0 for broadcast)
	TargetComponent uint8      // Component ID (0 for broadcast)
	Payload         [251]uint8 // Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields.  The entire content of this block is opaque unless you understand any the encoding message_type.  The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
}

File transfer message

func (*FileTransferProtocol) MsgID

func (self *FileTransferProtocol) MsgID() uint8

func (*FileTransferProtocol) MsgName

func (self *FileTransferProtocol) MsgName() string

func (*FileTransferProtocol) Pack

func (self *FileTransferProtocol) Pack(p *Packet) error

func (*FileTransferProtocol) Unpack

func (self *FileTransferProtocol) Unpack(p *Packet) error

type FlexifunctionBufferFunction

type FlexifunctionBufferFunction struct {
	FuncIndex       uint16   // Function index
	FuncCount       uint16   // Total count of functions
	DataAddress     uint16   // Address in the flexifunction data, Set to 0xFFFF to use address in target memory
	DataSize        uint16   // Size of the
	TargetSystem    uint8    // System ID
	TargetComponent uint8    // Component ID
	Data            [48]int8 // Settings data
}

Flexifunction type and parameters for component at function index from buffer

func (*FlexifunctionBufferFunction) MsgID

func (self *FlexifunctionBufferFunction) MsgID() uint8

func (*FlexifunctionBufferFunction) MsgName

func (self *FlexifunctionBufferFunction) MsgName() string

func (*FlexifunctionBufferFunction) Pack

func (self *FlexifunctionBufferFunction) Pack(p *Packet) error

func (*FlexifunctionBufferFunction) Unpack

func (self *FlexifunctionBufferFunction) Unpack(p *Packet) error

type FlexifunctionBufferFunctionAck

type FlexifunctionBufferFunctionAck struct {
	FuncIndex       uint16 // Function index
	Result          uint16 // result of acknowledge, 0=fail, 1=good
	TargetSystem    uint8  // System ID
	TargetComponent uint8  // Component ID
}

Flexifunction type and parameters for component at function index from buffer

func (*FlexifunctionBufferFunctionAck) MsgID

func (self *FlexifunctionBufferFunctionAck) MsgID() uint8

func (*FlexifunctionBufferFunctionAck) MsgName

func (self *FlexifunctionBufferFunctionAck) MsgName() string

func (*FlexifunctionBufferFunctionAck) Pack

func (*FlexifunctionBufferFunctionAck) Unpack

func (self *FlexifunctionBufferFunctionAck) Unpack(p *Packet) error

type FlexifunctionCommand

type FlexifunctionCommand struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
	CommandType     uint8 // Flexifunction command type
}

Acknowldge sucess or failure of a flexifunction command

func (*FlexifunctionCommand) MsgID

func (self *FlexifunctionCommand) MsgID() uint8

func (*FlexifunctionCommand) MsgName

func (self *FlexifunctionCommand) MsgName() string

func (*FlexifunctionCommand) Pack

func (self *FlexifunctionCommand) Pack(p *Packet) error

func (*FlexifunctionCommand) Unpack

func (self *FlexifunctionCommand) Unpack(p *Packet) error

type FlexifunctionCommandAck

type FlexifunctionCommandAck struct {
	CommandType uint16 // Command acknowledged
	Result      uint16 // result of acknowledge
}

Acknowldge sucess or failure of a flexifunction command

func (*FlexifunctionCommandAck) MsgID

func (self *FlexifunctionCommandAck) MsgID() uint8

func (*FlexifunctionCommandAck) MsgName

func (self *FlexifunctionCommandAck) MsgName() string

func (*FlexifunctionCommandAck) Pack

func (self *FlexifunctionCommandAck) Pack(p *Packet) error

func (*FlexifunctionCommandAck) Unpack

func (self *FlexifunctionCommandAck) Unpack(p *Packet) error

type FlexifunctionDirectory

type FlexifunctionDirectory struct {
	TargetSystem    uint8    // System ID
	TargetComponent uint8    // Component ID
	DirectoryType   uint8    // 0=inputs, 1=outputs
	StartIndex      uint8    // index of first directory entry to write
	Count           uint8    // count of directory entries to write
	DirectoryData   [48]int8 // Settings data
}

Acknowldge sucess or failure of a flexifunction command

func (*FlexifunctionDirectory) MsgID

func (self *FlexifunctionDirectory) MsgID() uint8

func (*FlexifunctionDirectory) MsgName

func (self *FlexifunctionDirectory) MsgName() string

func (*FlexifunctionDirectory) Pack

func (self *FlexifunctionDirectory) Pack(p *Packet) error

func (*FlexifunctionDirectory) Unpack

func (self *FlexifunctionDirectory) Unpack(p *Packet) error

type FlexifunctionDirectoryAck

type FlexifunctionDirectoryAck struct {
	Result          uint16 // result of acknowledge, 0=fail, 1=good
	TargetSystem    uint8  // System ID
	TargetComponent uint8  // Component ID
	DirectoryType   uint8  // 0=inputs, 1=outputs
	StartIndex      uint8  // index of first directory entry to write
	Count           uint8  // count of directory entries to write
}

Acknowldge sucess or failure of a flexifunction command

func (*FlexifunctionDirectoryAck) MsgID

func (self *FlexifunctionDirectoryAck) MsgID() uint8

func (*FlexifunctionDirectoryAck) MsgName

func (self *FlexifunctionDirectoryAck) MsgName() string

func (*FlexifunctionDirectoryAck) Pack

func (self *FlexifunctionDirectoryAck) Pack(p *Packet) error

func (*FlexifunctionDirectoryAck) Unpack

func (self *FlexifunctionDirectoryAck) Unpack(p *Packet) error

type FlexifunctionReadReq

type FlexifunctionReadReq struct {
	ReadReqType     int16 // Type of flexifunction data requested
	DataIndex       int16 // index into data where needed
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Reqest reading of flexifunction data

func (*FlexifunctionReadReq) MsgID

func (self *FlexifunctionReadReq) MsgID() uint8

func (*FlexifunctionReadReq) MsgName

func (self *FlexifunctionReadReq) MsgName() string

func (*FlexifunctionReadReq) Pack

func (self *FlexifunctionReadReq) Pack(p *Packet) error

func (*FlexifunctionReadReq) Unpack

func (self *FlexifunctionReadReq) Unpack(p *Packet) error

type FlexifunctionSet

type FlexifunctionSet struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Depreciated but used as a compiler flag. Do not remove

func (*FlexifunctionSet) MsgID

func (self *FlexifunctionSet) MsgID() uint8

func (*FlexifunctionSet) MsgName

func (self *FlexifunctionSet) MsgName() string

func (*FlexifunctionSet) Pack

func (self *FlexifunctionSet) Pack(p *Packet) error

func (*FlexifunctionSet) Unpack

func (self *FlexifunctionSet) Unpack(p *Packet) error

type FwSoaringData

type FwSoaringData struct {
	Timestamp            uint64  // Timestamp [ms]
	Timestampmodechanged uint64  // Timestamp since last mode change[ms]
	Currentupdraftspeed  float32 // Updraft speed at current/local airplane position [m/s]
	Xw                   float32 // Thermal core updraft strength [m/s]
	Xr                   float32 // Thermal radius [m]
	Xlat                 float32 // Thermal center latitude [deg]
	Xlon                 float32 // Thermal center longitude [deg]
	Varw                 float32 // Variance W
	Varr                 float32 // Variance R
	Varlat               float32 // Variance Lat
	Varlon               float32 // Variance Lon
	Loiterradius         float32 // Suggested loiter radius [m]
	Controlmode          uint8   // Control Mode [-]
	Valid                uint8   // Data valid [-]
}

Fixed-wing soaring (i.e. thermal seeking) data

func (*FwSoaringData) MsgID

func (self *FwSoaringData) MsgID() uint8

func (*FwSoaringData) MsgName

func (self *FwSoaringData) MsgName() string

func (*FwSoaringData) Pack

func (self *FwSoaringData) Pack(p *Packet) error

func (*FwSoaringData) Unpack

func (self *FwSoaringData) Unpack(p *Packet) error

type GimbalAxisCalibrationProgress

type GimbalAxisCalibrationProgress struct {
	CalibrationAxis     uint8 // Which gimbal axis we're reporting calibration progress for
	CalibrationProgress uint8 // The current calibration progress for this axis, 0x64=100%
	CalibrationStatus   uint8 // The status of the running calibration
}

Reports progress and success or failure of gimbal axis calibration procedure

func (*GimbalAxisCalibrationProgress) MsgID

func (self *GimbalAxisCalibrationProgress) MsgID() uint8

func (*GimbalAxisCalibrationProgress) MsgName

func (self *GimbalAxisCalibrationProgress) MsgName() string

func (*GimbalAxisCalibrationProgress) Pack

func (*GimbalAxisCalibrationProgress) Unpack

func (self *GimbalAxisCalibrationProgress) Unpack(p *Packet) error

type GimbalControl

type GimbalControl struct {
	DemandedRateX   float32 // Demanded angular rate X (rad/s)
	DemandedRateY   float32 // Demanded angular rate Y (rad/s)
	DemandedRateZ   float32 // Demanded angular rate Z (rad/s)
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
}

Control message for rate gimbal

func (*GimbalControl) MsgID

func (self *GimbalControl) MsgID() uint8

func (*GimbalControl) MsgName

func (self *GimbalControl) MsgName() string

func (*GimbalControl) Pack

func (self *GimbalControl) Pack(p *Packet) error

func (*GimbalControl) Unpack

func (self *GimbalControl) Unpack(p *Packet) error

type GimbalEraseFirmwareAndConfig

type GimbalEraseFirmwareAndConfig struct {
	Knock           uint32 // Knock value to confirm this is a valid request
	TargetSystem    uint8  // System ID
	TargetComponent uint8  // Component ID
}

Commands the gimbal to erase its firmware image and flash configuration, leaving only the bootloader. The gimbal will then reboot into the bootloader, ready for the load of a new application firmware image. Erasing the flash configuration will cause the gimbal to re-perform axis calibration when a new firmware image is loaded, and will cause all tuning parameters to return to their factory defaults. WARNING: sending this command will render a gimbal inoperable until a new firmware image is loaded onto it. For this reason, a particular "knock" value must be sent for the command to take effect. Use this command at your own risk

func (*GimbalEraseFirmwareAndConfig) MsgID

func (self *GimbalEraseFirmwareAndConfig) MsgID() uint8

func (*GimbalEraseFirmwareAndConfig) MsgName

func (self *GimbalEraseFirmwareAndConfig) MsgName() string

func (*GimbalEraseFirmwareAndConfig) Pack

func (self *GimbalEraseFirmwareAndConfig) Pack(p *Packet) error

func (*GimbalEraseFirmwareAndConfig) Unpack

func (self *GimbalEraseFirmwareAndConfig) Unpack(p *Packet) error

type GimbalFactoryParametersLoaded

type GimbalFactoryParametersLoaded struct {
	Dummy uint8 // Dummy field because mavgen doesn't allow messages with no fields
}

Sent by the gimbal after the factory parameters are successfully loaded, to inform the factory software that the load is complete

func (*GimbalFactoryParametersLoaded) MsgID

func (self *GimbalFactoryParametersLoaded) MsgID() uint8

func (*GimbalFactoryParametersLoaded) MsgName

func (self *GimbalFactoryParametersLoaded) MsgName() string

func (*GimbalFactoryParametersLoaded) Pack

func (*GimbalFactoryParametersLoaded) Unpack

func (self *GimbalFactoryParametersLoaded) Unpack(p *Packet) error

type GimbalHomeOffsetCalibrationResult

type GimbalHomeOffsetCalibrationResult struct {
	CalibrationResult uint8 // The result of the home offset calibration
}

Sent by the gimbal after it receives a SET_HOME_OFFSETS message to indicate the result of the home offset calibration

func (*GimbalHomeOffsetCalibrationResult) MsgID

func (*GimbalHomeOffsetCalibrationResult) MsgName

func (self *GimbalHomeOffsetCalibrationResult) MsgName() string

func (*GimbalHomeOffsetCalibrationResult) Pack

func (*GimbalHomeOffsetCalibrationResult) Unpack

type GimbalPerformFactoryTests

type GimbalPerformFactoryTests struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Command the gimbal to perform a series of factory tests. Should not be needed by end users

func (*GimbalPerformFactoryTests) MsgID

func (self *GimbalPerformFactoryTests) MsgID() uint8

func (*GimbalPerformFactoryTests) MsgName

func (self *GimbalPerformFactoryTests) MsgName() string

func (*GimbalPerformFactoryTests) Pack

func (self *GimbalPerformFactoryTests) Pack(p *Packet) error

func (*GimbalPerformFactoryTests) Unpack

func (self *GimbalPerformFactoryTests) Unpack(p *Packet) error

type GimbalReport

type GimbalReport struct {
	DeltaTime       float32 // Time since last update (seconds)
	DeltaAngleX     float32 // Delta angle X (radians)
	DeltaAngleY     float32 // Delta angle Y (radians)
	DeltaAngleZ     float32 // Delta angle X (radians)
	DeltaVelocityX  float32 // Delta velocity X (m/s)
	DeltaVelocityY  float32 // Delta velocity Y (m/s)
	DeltaVelocityZ  float32 // Delta velocity Z (m/s)
	JointRoll       float32 //  Joint ROLL (radians)
	JointEl         float32 //  Joint EL (radians)
	JointAz         float32 //  Joint AZ (radians)
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
}

3 axis gimbal measurements

func (*GimbalReport) MsgID

func (self *GimbalReport) MsgID() uint8

func (*GimbalReport) MsgName

func (self *GimbalReport) MsgName() string

func (*GimbalReport) Pack

func (self *GimbalReport) Pack(p *Packet) error

func (*GimbalReport) Unpack

func (self *GimbalReport) Unpack(p *Packet) error

type GimbalReportFactoryTestsProgress

type GimbalReportFactoryTestsProgress struct {
	Test                uint8 // Which factory test is currently running
	TestSection         uint8 // Which section of the test is currently running.  The meaning of this is test-dependent
	TestSectionProgress uint8 // The progress of the current test section, 0x64=100%
	TestStatus          uint8 // The status of the currently executing test section.  The meaning of this is test and section-dependent
}

Reports the current status of a section of a running factory test

func (*GimbalReportFactoryTestsProgress) MsgID

func (*GimbalReportFactoryTestsProgress) MsgName

func (self *GimbalReportFactoryTestsProgress) MsgName() string

func (*GimbalReportFactoryTestsProgress) Pack

func (*GimbalReportFactoryTestsProgress) Unpack

type GimbalReset

type GimbalReset struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Causes the gimbal to reset and boot as if it was just powered on

func (*GimbalReset) MsgID

func (self *GimbalReset) MsgID() uint8

func (*GimbalReset) MsgName

func (self *GimbalReset) MsgName() string

func (*GimbalReset) Pack

func (self *GimbalReset) Pack(p *Packet) error

func (*GimbalReset) Unpack

func (self *GimbalReset) Unpack(p *Packet) error

type GimbalSetFactoryParameters

type GimbalSetFactoryParameters struct {
	Magic1          uint32 // Magic number 1 for validation
	Magic2          uint32 // Magic number 2 for validation
	Magic3          uint32 // Magic number 3 for validation
	SerialNumberPt1 uint32 // Unit Serial Number Part 1 (part code, design, language/country)
	SerialNumberPt2 uint32 // Unit Serial Number Part 2 (option, year, month)
	SerialNumberPt3 uint32 // Unit Serial Number Part 3 (incrementing serial number per month)
	AssemblyYear    uint16 // Assembly Date Year
	TargetSystem    uint8  // System ID
	TargetComponent uint8  // Component ID
	AssemblyMonth   uint8  // Assembly Date Month
	AssemblyDay     uint8  // Assembly Date Day
	AssemblyHour    uint8  // Assembly Time Hour
	AssemblyMinute  uint8  // Assembly Time Minute
	AssemblySecond  uint8  // Assembly Time Second
}

Set factory configuration parameters (such as assembly date and time, and serial number). This is only intended to be used during manufacture, not by end users, so it is protected by a simple checksum of sorts (this won't stop anybody determined, it's mostly just to keep the average user from trying to modify these values. This will need to be revisited if that isn't adequate.

func (*GimbalSetFactoryParameters) MsgID

func (self *GimbalSetFactoryParameters) MsgID() uint8

func (*GimbalSetFactoryParameters) MsgName

func (self *GimbalSetFactoryParameters) MsgName() string

func (*GimbalSetFactoryParameters) Pack

func (self *GimbalSetFactoryParameters) Pack(p *Packet) error

func (*GimbalSetFactoryParameters) Unpack

func (self *GimbalSetFactoryParameters) Unpack(p *Packet) error

type GimbalSetHomeOffsets

type GimbalSetHomeOffsets struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Instructs the gimbal to set its current position as its new home position. Will primarily be used for factory calibration

func (*GimbalSetHomeOffsets) MsgID

func (self *GimbalSetHomeOffsets) MsgID() uint8

func (*GimbalSetHomeOffsets) MsgName

func (self *GimbalSetHomeOffsets) MsgName() string

func (*GimbalSetHomeOffsets) Pack

func (self *GimbalSetHomeOffsets) Pack(p *Packet) error

func (*GimbalSetHomeOffsets) Unpack

func (self *GimbalSetHomeOffsets) Unpack(p *Packet) error

type GlobalPositionInt

type GlobalPositionInt struct {
	TimeBootMs  uint32 // Timestamp (milliseconds since system boot)
	Lat         int32  // Latitude, expressed as * 1E7
	Lon         int32  // Longitude, expressed as * 1E7
	Alt         int32  // Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
	RelativeAlt int32  // Altitude above ground in meters, expressed as * 1000 (millimeters)
	Vx          int16  // Ground X Speed (Latitude), expressed as m/s * 100
	Vy          int16  // Ground Y Speed (Longitude), expressed as m/s * 100
	Vz          int16  // Ground Z Speed (Altitude), expressed as m/s * 100
	Hdg         uint16 // Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
}

The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It

is designed as scaled integer message since the resolution of float is not sufficient.

func (*GlobalPositionInt) MsgID

func (self *GlobalPositionInt) MsgID() uint8

func (*GlobalPositionInt) MsgName

func (self *GlobalPositionInt) MsgName() string

func (*GlobalPositionInt) Pack

func (self *GlobalPositionInt) Pack(p *Packet) error

func (*GlobalPositionInt) Unpack

func (self *GlobalPositionInt) Unpack(p *Packet) error

type GlobalPositionIntCov

type GlobalPositionIntCov struct {
	TimeUtc       uint64      // Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
	TimeBootMs    uint32      // Timestamp (milliseconds since system boot)
	Lat           int32       // Latitude, expressed as degrees * 1E7
	Lon           int32       // Longitude, expressed as degrees * 1E7
	Alt           int32       // Altitude in meters, expressed as * 1000 (millimeters), above MSL
	RelativeAlt   int32       // Altitude above ground in meters, expressed as * 1000 (millimeters)
	Vx            float32     // Ground X Speed (Latitude), expressed as m/s
	Vy            float32     // Ground Y Speed (Longitude), expressed as m/s
	Vz            float32     // Ground Z Speed (Altitude), expressed as m/s
	Covariance    [36]float32 // Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
	EstimatorType uint8       // Class id of the estimator this estimate originated from.
}

The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset.

func (*GlobalPositionIntCov) MsgID

func (self *GlobalPositionIntCov) MsgID() uint8

func (*GlobalPositionIntCov) MsgName

func (self *GlobalPositionIntCov) MsgName() string

func (*GlobalPositionIntCov) Pack

func (self *GlobalPositionIntCov) Pack(p *Packet) error

func (*GlobalPositionIntCov) Unpack

func (self *GlobalPositionIntCov) Unpack(p *Packet) error

type GlobalVisionPositionEstimate

type GlobalVisionPositionEstimate struct {
	Usec  uint64  // Timestamp (microseconds, synced to UNIX time or since system boot)
	X     float32 // Global X position
	Y     float32 // Global Y position
	Z     float32 // Global Z position
	Roll  float32 // Roll angle in rad
	Pitch float32 // Pitch angle in rad
	Yaw   float32 // Yaw angle in rad
}

func (*GlobalVisionPositionEstimate) MsgID

func (self *GlobalVisionPositionEstimate) MsgID() uint8

func (*GlobalVisionPositionEstimate) MsgName

func (self *GlobalVisionPositionEstimate) MsgName() string

func (*GlobalVisionPositionEstimate) Pack

func (self *GlobalVisionPositionEstimate) Pack(p *Packet) error

func (*GlobalVisionPositionEstimate) Unpack

func (self *GlobalVisionPositionEstimate) Unpack(p *Packet) error

type GoproCommand

type GoproCommand struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
	GpCmdName1      uint8 // First character of the 2 character GoPro command
	GpCmdName2      uint8 // Second character of the 2 character GoPro command
	GpCmdParm       uint8 // Parameter for the command
}

Send a command to a HeroBus attached GoPro. Will generate a GOPRO_RESPONSE message with results of the command

func (*GoproCommand) MsgID

func (self *GoproCommand) MsgID() uint8

func (*GoproCommand) MsgName

func (self *GoproCommand) MsgName() string

func (*GoproCommand) Pack

func (self *GoproCommand) Pack(p *Packet) error

func (*GoproCommand) Unpack

func (self *GoproCommand) Unpack(p *Packet) error

type GoproPowerOff

type GoproPowerOff struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Instruct a HeroBus attached GoPro to power off

func (*GoproPowerOff) MsgID

func (self *GoproPowerOff) MsgID() uint8

func (*GoproPowerOff) MsgName

func (self *GoproPowerOff) MsgName() string

func (*GoproPowerOff) Pack

func (self *GoproPowerOff) Pack(p *Packet) error

func (*GoproPowerOff) Unpack

func (self *GoproPowerOff) Unpack(p *Packet) error

type GoproPowerOn

type GoproPowerOn struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Instruct a HeroBus attached GoPro to power on

func (*GoproPowerOn) MsgID

func (self *GoproPowerOn) MsgID() uint8

func (*GoproPowerOn) MsgName

func (self *GoproPowerOn) MsgName() string

func (*GoproPowerOn) Pack

func (self *GoproPowerOn) Pack(p *Packet) error

func (*GoproPowerOn) Unpack

func (self *GoproPowerOn) Unpack(p *Packet) error

type GoproResponse

type GoproResponse struct {
	GpCmdResult           uint16 // Result of the command attempt to the GoPro, as defined by GOPRO_CMD_RESULT enum.
	GpCmdName1            uint8  // First character of the 2 character GoPro command that generated this response
	GpCmdName2            uint8  // Second character of the 2 character GoPro command that generated this response
	GpCmdResponseStatus   uint8  // Response byte from the GoPro's response to the command.  0 = Success, 1 = Failure
	GpCmdResponseArgument uint8  // Response argument from the GoPro's response to the command
}

Response to a command sent to a HeroBus attached GoPro with a GOPRO_COMMAND message. Contains response from the camera as well as information about any errors encountered while attempting to communicate with the camera

func (*GoproResponse) MsgID

func (self *GoproResponse) MsgID() uint8

func (*GoproResponse) MsgName

func (self *GoproResponse) MsgName() string

func (*GoproResponse) Pack

func (self *GoproResponse) Pack(p *Packet) error

func (*GoproResponse) Unpack

func (self *GoproResponse) Unpack(p *Packet) error

type Gps2Raw

type Gps2Raw struct {
	TimeUsec          uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	Lat               int32  // Latitude (WGS84), in degrees * 1E7
	Lon               int32  // Longitude (WGS84), in degrees * 1E7
	Alt               int32  // Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
	DgpsAge           uint32 // Age of DGPS info
	Eph               uint16 // GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
	Epv               uint16 // GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
	Vel               uint16 // GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
	Cog               uint16 // Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
	FixType           uint8  // 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
	SatellitesVisible uint8  // Number of satellites visible. If unknown, set to 255
	DgpsNumch         uint8  // Number of DGPS satellites
}

Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS frame).

func (*Gps2Raw) MsgID

func (self *Gps2Raw) MsgID() uint8

func (*Gps2Raw) MsgName

func (self *Gps2Raw) MsgName() string

func (*Gps2Raw) Pack

func (self *Gps2Raw) Pack(p *Packet) error

func (*Gps2Raw) Unpack

func (self *Gps2Raw) Unpack(p *Packet) error

type Gps2Rtk

type Gps2Rtk struct {
	TimeLastBaselineMs uint32 // Time since boot of last baseline message received in ms.
	Tow                uint32 // GPS Time of Week of last baseline
	BaselineAMm        int32  // Current baseline in ECEF x or NED north component in mm.
	BaselineBMm        int32  // Current baseline in ECEF y or NED east component in mm.
	BaselineCMm        int32  // Current baseline in ECEF z or NED down component in mm.
	Accuracy           uint32 // Current estimate of baseline accuracy.
	IarNumHypotheses   int32  // Current number of integer ambiguity hypotheses.
	Wn                 uint16 // GPS Week Number of last baseline
	RtkReceiverId      uint8  // Identification of connected RTK receiver.
	RtkHealth          uint8  // GPS-specific health report for RTK data.
	RtkRate            uint8  // Rate of baseline messages being received by GPS, in HZ
	Nsats              uint8  // Current number of sats used for RTK calculation.
	BaselineCoordsType uint8  // Coordinate system of baseline. 0 == ECEF, 1 == NED
}

RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting

func (*Gps2Rtk) MsgID

func (self *Gps2Rtk) MsgID() uint8

func (*Gps2Rtk) MsgName

func (self *Gps2Rtk) MsgName() string

func (*Gps2Rtk) Pack

func (self *Gps2Rtk) Pack(p *Packet) error

func (*Gps2Rtk) Unpack

func (self *Gps2Rtk) Unpack(p *Packet) error

type GpsGlobalOrigin

type GpsGlobalOrigin struct {
	Latitude  int32 // Latitude (WGS84), in degrees * 1E7
	Longitude int32 // Longitude (WGS84), in degrees * 1E7
	Altitude  int32 // Altitude (AMSL), in meters * 1000 (positive for up)
}

Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position

func (*GpsGlobalOrigin) MsgID

func (self *GpsGlobalOrigin) MsgID() uint8

func (*GpsGlobalOrigin) MsgName

func (self *GpsGlobalOrigin) MsgName() string

func (*GpsGlobalOrigin) Pack

func (self *GpsGlobalOrigin) Pack(p *Packet) error

func (*GpsGlobalOrigin) Unpack

func (self *GpsGlobalOrigin) Unpack(p *Packet) error

type GpsInjectData

type GpsInjectData struct {
	TargetSystem    uint8      // System ID
	TargetComponent uint8      // Component ID
	Len             uint8      // data length
	Data            [110]uint8 // raw data (110 is enough for 12 satellites of RTCMv2)
}

data for injecting into the onboard GPS (used for DGPS)

func (*GpsInjectData) MsgID

func (self *GpsInjectData) MsgID() uint8

func (*GpsInjectData) MsgName

func (self *GpsInjectData) MsgName() string

func (*GpsInjectData) Pack

func (self *GpsInjectData) Pack(p *Packet) error

func (*GpsInjectData) Unpack

func (self *GpsInjectData) Unpack(p *Packet) error

type GpsRawInt

type GpsRawInt struct {
	TimeUsec          uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	Lat               int32  // Latitude (WGS84), in degrees * 1E7
	Lon               int32  // Longitude (WGS84), in degrees * 1E7
	Alt               int32  // Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
	Eph               uint16 // GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
	Epv               uint16 // GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
	Vel               uint16 // GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
	Cog               uint16 // Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
	FixType           uint8  // 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
	SatellitesVisible uint8  // Number of satellites visible. If unknown, set to 255
}

The global position, as returned by the Global Positioning System (GPS). This is

NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame).

func (*GpsRawInt) MsgID

func (self *GpsRawInt) MsgID() uint8

func (*GpsRawInt) MsgName

func (self *GpsRawInt) MsgName() string

func (*GpsRawInt) Pack

func (self *GpsRawInt) Pack(p *Packet) error

func (*GpsRawInt) Unpack

func (self *GpsRawInt) Unpack(p *Packet) error

type GpsRtk

type GpsRtk struct {
	TimeLastBaselineMs uint32 // Time since boot of last baseline message received in ms.
	Tow                uint32 // GPS Time of Week of last baseline
	BaselineAMm        int32  // Current baseline in ECEF x or NED north component in mm.
	BaselineBMm        int32  // Current baseline in ECEF y or NED east component in mm.
	BaselineCMm        int32  // Current baseline in ECEF z or NED down component in mm.
	Accuracy           uint32 // Current estimate of baseline accuracy.
	IarNumHypotheses   int32  // Current number of integer ambiguity hypotheses.
	Wn                 uint16 // GPS Week Number of last baseline
	RtkReceiverId      uint8  // Identification of connected RTK receiver.
	RtkHealth          uint8  // GPS-specific health report for RTK data.
	RtkRate            uint8  // Rate of baseline messages being received by GPS, in HZ
	Nsats              uint8  // Current number of sats used for RTK calculation.
	BaselineCoordsType uint8  // Coordinate system of baseline. 0 == ECEF, 1 == NED
}

RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting

func (*GpsRtk) MsgID

func (self *GpsRtk) MsgID() uint8

func (*GpsRtk) MsgName

func (self *GpsRtk) MsgName() string

func (*GpsRtk) Pack

func (self *GpsRtk) Pack(p *Packet) error

func (*GpsRtk) Unpack

func (self *GpsRtk) Unpack(p *Packet) error

type GpsStatus

type GpsStatus struct {
	SatellitesVisible  uint8     // Number of satellites visible
	SatellitePrn       [20]uint8 // Global satellite ID
	SatelliteUsed      [20]uint8 // 0: Satellite not used, 1: used for localization
	SatelliteElevation [20]uint8 // Elevation (0: right on top of receiver, 90: on the horizon) of satellite
	SatelliteAzimuth   [20]uint8 // Direction of satellite, 0: 0 deg, 255: 360 deg.
	SatelliteSnr       [20]uint8 // Signal to noise ratio of satellite
}

The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites.

func (*GpsStatus) MsgID

func (self *GpsStatus) MsgID() uint8

func (*GpsStatus) MsgName

func (self *GpsStatus) MsgName() string

func (*GpsStatus) Pack

func (self *GpsStatus) Pack(p *Packet) error

func (*GpsStatus) Unpack

func (self *GpsStatus) Unpack(p *Packet) error

type Heartbeat

type Heartbeat struct {
	CustomMode     uint32 // A bitfield for use for autopilot-specific flags.
	Type           uint8  // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
	Autopilot      uint8  // Autopilot type / class. defined in MAV_AUTOPILOT ENUM
	BaseMode       uint8  // System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h
	SystemStatus   uint8  // System status flag, see MAV_STATE ENUM
	MavlinkVersion uint8  // MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version
}

The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).

func (*Heartbeat) MsgID

func (self *Heartbeat) MsgID() uint8

func (*Heartbeat) MsgName

func (self *Heartbeat) MsgName() string

func (*Heartbeat) Pack

func (self *Heartbeat) Pack(p *Packet) error

func (*Heartbeat) Unpack

func (self *Heartbeat) Unpack(p *Packet) error

type HighresImu

type HighresImu struct {
	TimeUsec      uint64  // Timestamp (microseconds, synced to UNIX time or since system boot)
	Xacc          float32 // X acceleration (m/s^2)
	Yacc          float32 // Y acceleration (m/s^2)
	Zacc          float32 // Z acceleration (m/s^2)
	Xgyro         float32 // Angular speed around X axis (rad / sec)
	Ygyro         float32 // Angular speed around Y axis (rad / sec)
	Zgyro         float32 // Angular speed around Z axis (rad / sec)
	Xmag          float32 // X Magnetic field (Gauss)
	Ymag          float32 // Y Magnetic field (Gauss)
	Zmag          float32 // Z Magnetic field (Gauss)
	AbsPressure   float32 // Absolute pressure in millibar
	DiffPressure  float32 // Differential pressure in millibar
	PressureAlt   float32 // Altitude calculated from pressure
	Temperature   float32 // Temperature in degrees celsius
	FieldsUpdated uint16  // Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
}

The IMU readings in SI units in NED body frame

func (*HighresImu) MsgID

func (self *HighresImu) MsgID() uint8

func (*HighresImu) MsgName

func (self *HighresImu) MsgName() string

func (*HighresImu) Pack

func (self *HighresImu) Pack(p *Packet) error

func (*HighresImu) Unpack

func (self *HighresImu) Unpack(p *Packet) error

type HilControls

type HilControls struct {
	TimeUsec      uint64  // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	RollAilerons  float32 // Control output -1 .. 1
	PitchElevator float32 // Control output -1 .. 1
	YawRudder     float32 // Control output -1 .. 1
	Throttle      float32 // Throttle 0 .. 1
	Aux1          float32 // Aux 1, -1 .. 1
	Aux2          float32 // Aux 2, -1 .. 1
	Aux3          float32 // Aux 3, -1 .. 1
	Aux4          float32 // Aux 4, -1 .. 1
	Mode          uint8   // System mode (MAV_MODE)
	NavMode       uint8   // Navigation mode (MAV_NAV_MODE)
}

Sent from autopilot to simulation. Hardware in the loop control outputs

func (*HilControls) MsgID

func (self *HilControls) MsgID() uint8

func (*HilControls) MsgName

func (self *HilControls) MsgName() string

func (*HilControls) Pack

func (self *HilControls) Pack(p *Packet) error

func (*HilControls) Unpack

func (self *HilControls) Unpack(p *Packet) error

type HilGps

type HilGps struct {
	TimeUsec          uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	Lat               int32  // Latitude (WGS84), in degrees * 1E7
	Lon               int32  // Longitude (WGS84), in degrees * 1E7
	Alt               int32  // Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
	Eph               uint16 // GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
	Epv               uint16 // GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535
	Vel               uint16 // GPS ground speed (m/s * 100). If unknown, set to: 65535
	Vn                int16  // GPS velocity in cm/s in NORTH direction in earth-fixed NED frame
	Ve                int16  // GPS velocity in cm/s in EAST direction in earth-fixed NED frame
	Vd                int16  // GPS velocity in cm/s in DOWN direction in earth-fixed NED frame
	Cog               uint16 // Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
	FixType           uint8  // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
	SatellitesVisible uint8  // Number of satellites visible. If unknown, set to 255
}

The global position, as returned by the Global Positioning System (GPS). This is

NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame).

func (*HilGps) MsgID

func (self *HilGps) MsgID() uint8

func (*HilGps) MsgName

func (self *HilGps) MsgName() string

func (*HilGps) Pack

func (self *HilGps) Pack(p *Packet) error

func (*HilGps) Unpack

func (self *HilGps) Unpack(p *Packet) error

type HilOpticalFlow

type HilOpticalFlow struct {
	TimeUsec            uint64  // Timestamp (microseconds, synced to UNIX time or since system boot)
	IntegrationTimeUs   uint32  // Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
	IntegratedX         float32 // Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
	IntegratedY         float32 // Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
	IntegratedXgyro     float32 // RH rotation around X axis (rad)
	IntegratedYgyro     float32 // RH rotation around Y axis (rad)
	IntegratedZgyro     float32 // RH rotation around Z axis (rad)
	TimeDeltaDistanceUs uint32  // Time in microseconds since the distance was sampled.
	Distance            float32 // Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
	Temperature         int16   // Temperature * 100 in centi-degrees Celsius
	SensorId            uint8   // Sensor ID
	Quality             uint8   // Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
}

Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor)

func (*HilOpticalFlow) MsgID

func (self *HilOpticalFlow) MsgID() uint8

func (*HilOpticalFlow) MsgName

func (self *HilOpticalFlow) MsgName() string

func (*HilOpticalFlow) Pack

func (self *HilOpticalFlow) Pack(p *Packet) error

func (*HilOpticalFlow) Unpack

func (self *HilOpticalFlow) Unpack(p *Packet) error

type HilRcInputsRaw

type HilRcInputsRaw struct {
	TimeUsec  uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	Chan1Raw  uint16 // RC channel 1 value, in microseconds
	Chan2Raw  uint16 // RC channel 2 value, in microseconds
	Chan3Raw  uint16 // RC channel 3 value, in microseconds
	Chan4Raw  uint16 // RC channel 4 value, in microseconds
	Chan5Raw  uint16 // RC channel 5 value, in microseconds
	Chan6Raw  uint16 // RC channel 6 value, in microseconds
	Chan7Raw  uint16 // RC channel 7 value, in microseconds
	Chan8Raw  uint16 // RC channel 8 value, in microseconds
	Chan9Raw  uint16 // RC channel 9 value, in microseconds
	Chan10Raw uint16 // RC channel 10 value, in microseconds
	Chan11Raw uint16 // RC channel 11 value, in microseconds
	Chan12Raw uint16 // RC channel 12 value, in microseconds
	Rssi      uint8  // Receive signal strength indicator, 0: 0%, 255: 100%
}

Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.

func (*HilRcInputsRaw) MsgID

func (self *HilRcInputsRaw) MsgID() uint8

func (*HilRcInputsRaw) MsgName

func (self *HilRcInputsRaw) MsgName() string

func (*HilRcInputsRaw) Pack

func (self *HilRcInputsRaw) Pack(p *Packet) error

func (*HilRcInputsRaw) Unpack

func (self *HilRcInputsRaw) Unpack(p *Packet) error

type HilSensor

type HilSensor struct {
	TimeUsec      uint64  // Timestamp (microseconds, synced to UNIX time or since system boot)
	Xacc          float32 // X acceleration (m/s^2)
	Yacc          float32 // Y acceleration (m/s^2)
	Zacc          float32 // Z acceleration (m/s^2)
	Xgyro         float32 // Angular speed around X axis in body frame (rad / sec)
	Ygyro         float32 // Angular speed around Y axis in body frame (rad / sec)
	Zgyro         float32 // Angular speed around Z axis in body frame (rad / sec)
	Xmag          float32 // X Magnetic field (Gauss)
	Ymag          float32 // Y Magnetic field (Gauss)
	Zmag          float32 // Z Magnetic field (Gauss)
	AbsPressure   float32 // Absolute pressure in millibar
	DiffPressure  float32 // Differential pressure (airspeed) in millibar
	PressureAlt   float32 // Altitude calculated from pressure
	Temperature   float32 // Temperature in degrees celsius
	FieldsUpdated uint32  // Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
}

The IMU readings in SI units in NED body frame

func (*HilSensor) MsgID

func (self *HilSensor) MsgID() uint8

func (*HilSensor) MsgName

func (self *HilSensor) MsgName() string

func (*HilSensor) Pack

func (self *HilSensor) Pack(p *Packet) error

func (*HilSensor) Unpack

func (self *HilSensor) Unpack(p *Packet) error

type HilState

type HilState struct {
	TimeUsec   uint64  // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	Roll       float32 // Roll angle (rad)
	Pitch      float32 // Pitch angle (rad)
	Yaw        float32 // Yaw angle (rad)
	Rollspeed  float32 // Body frame roll / phi angular speed (rad/s)
	Pitchspeed float32 // Body frame pitch / theta angular speed (rad/s)
	Yawspeed   float32 // Body frame yaw / psi angular speed (rad/s)
	Lat        int32   // Latitude, expressed as * 1E7
	Lon        int32   // Longitude, expressed as * 1E7
	Alt        int32   // Altitude in meters, expressed as * 1000 (millimeters)
	Vx         int16   // Ground X Speed (Latitude), expressed as m/s * 100
	Vy         int16   // Ground Y Speed (Longitude), expressed as m/s * 100
	Vz         int16   // Ground Z Speed (Altitude), expressed as m/s * 100
	Xacc       int16   // X acceleration (mg)
	Yacc       int16   // Y acceleration (mg)
	Zacc       int16   // Z acceleration (mg)
}

DEPRECATED PACKET! Suffers from missing airspeed fields and singularities due to Euler angles. Please use HIL_STATE_QUATERNION instead. Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations.

func (*HilState) MsgID

func (self *HilState) MsgID() uint8

func (*HilState) MsgName

func (self *HilState) MsgName() string

func (*HilState) Pack

func (self *HilState) Pack(p *Packet) error

func (*HilState) Unpack

func (self *HilState) Unpack(p *Packet) error

type HilStateQuaternion

type HilStateQuaternion struct {
	TimeUsec           uint64     // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	AttitudeQuaternion [4]float32 // Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
	Rollspeed          float32    // Body frame roll / phi angular speed (rad/s)
	Pitchspeed         float32    // Body frame pitch / theta angular speed (rad/s)
	Yawspeed           float32    // Body frame yaw / psi angular speed (rad/s)
	Lat                int32      // Latitude, expressed as * 1E7
	Lon                int32      // Longitude, expressed as * 1E7
	Alt                int32      // Altitude in meters, expressed as * 1000 (millimeters)
	Vx                 int16      // Ground X Speed (Latitude), expressed as m/s * 100
	Vy                 int16      // Ground Y Speed (Longitude), expressed as m/s * 100
	Vz                 int16      // Ground Z Speed (Altitude), expressed as m/s * 100
	IndAirspeed        uint16     // Indicated airspeed, expressed as m/s * 100
	TrueAirspeed       uint16     // True airspeed, expressed as m/s * 100
	Xacc               int16      // X acceleration (mg)
	Yacc               int16      // Y acceleration (mg)
	Zacc               int16      // Z acceleration (mg)
}

Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations.

func (*HilStateQuaternion) MsgID

func (self *HilStateQuaternion) MsgID() uint8

func (*HilStateQuaternion) MsgName

func (self *HilStateQuaternion) MsgName() string

func (*HilStateQuaternion) Pack

func (self *HilStateQuaternion) Pack(p *Packet) error

func (*HilStateQuaternion) Unpack

func (self *HilStateQuaternion) Unpack(p *Packet) error

type HomePosition

type HomePosition struct {
	Latitude  int32      // Latitude (WGS84), in degrees * 1E7
	Longitude int32      // Longitude (WGS84, in degrees * 1E7
	Altitude  int32      // Altitude (AMSL), in meters * 1000 (positive for up)
	X         float32    // Local X position of this position in the local coordinate frame
	Y         float32    // Local Y position of this position in the local coordinate frame
	Z         float32    // Local Z position of this position in the local coordinate frame
	Q         [4]float32 // World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
	ApproachX float32    // 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.
	ApproachY float32    // 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.
	ApproachZ float32    // 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.
}

This message can be requested by sending the MAV_CMD_GET_HOME_POSITION command. The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The position the system will return to and land on. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector.

func (*HomePosition) MsgID

func (self *HomePosition) MsgID() uint8

func (*HomePosition) MsgName

func (self *HomePosition) MsgName() string

func (*HomePosition) Pack

func (self *HomePosition) Pack(p *Packet) error

func (*HomePosition) Unpack

func (self *HomePosition) Unpack(p *Packet) error

type Hwstatus

type Hwstatus struct {
	Vcc    uint16 // board voltage (mV)
	I2cerr uint8  // I2C error count
}

Status of key hardware

func (*Hwstatus) MsgID

func (self *Hwstatus) MsgID() uint8

func (*Hwstatus) MsgName

func (self *Hwstatus) MsgName() string

func (*Hwstatus) Pack

func (self *Hwstatus) Pack(p *Packet) error

func (*Hwstatus) Unpack

func (self *Hwstatus) Unpack(p *Packet) error

type ImageAvailable

type ImageAvailable struct {
	CamId       uint64  // Camera id
	Timestamp   uint64  // Timestamp
	ValidUntil  uint64  // Until which timestamp this buffer will stay valid
	ImgSeq      uint32  // The image sequence number
	ImgBufIndex uint32  // Position of the image in the buffer, starts with 0
	Key         uint32  // Shared memory area key
	Exposure    uint32  // Exposure time, in microseconds
	Gain        float32 // Camera gain
	Roll        float32 // Roll angle in rad
	Pitch       float32 // Pitch angle in rad
	Yaw         float32 // Yaw angle in rad
	LocalZ      float32 // Local frame Z coordinate (height over ground)
	Lat         float32 // GPS X coordinate
	Lon         float32 // GPS Y coordinate
	Alt         float32 // Global frame altitude
	GroundX     float32 // Ground truth X
	GroundY     float32 // Ground truth Y
	GroundZ     float32 // Ground truth Z
	Width       uint16  // Image width
	Height      uint16  // Image height
	Depth       uint16  // Image depth
	CamNo       uint8   // Camera # (starts with 0)
	Channels    uint8   // Image channels
}

func (*ImageAvailable) MsgID

func (self *ImageAvailable) MsgID() uint8

func (*ImageAvailable) MsgName

func (self *ImageAvailable) MsgName() string

func (*ImageAvailable) Pack

func (self *ImageAvailable) Pack(p *Packet) error

func (*ImageAvailable) Unpack

func (self *ImageAvailable) Unpack(p *Packet) error

type ImageTriggerControl

type ImageTriggerControl struct {
	Enable uint8 // 0 to disable, 1 to enable
}

func (*ImageTriggerControl) MsgID

func (self *ImageTriggerControl) MsgID() uint8

func (*ImageTriggerControl) MsgName

func (self *ImageTriggerControl) MsgName() string

func (*ImageTriggerControl) Pack

func (self *ImageTriggerControl) Pack(p *Packet) error

func (*ImageTriggerControl) Unpack

func (self *ImageTriggerControl) Unpack(p *Packet) error

type ImageTriggered

type ImageTriggered struct {
	Timestamp uint64  // Timestamp
	Seq       uint32  // IMU seq
	Roll      float32 // Roll angle in rad
	Pitch     float32 // Pitch angle in rad
	Yaw       float32 // Yaw angle in rad
	LocalZ    float32 // Local frame Z coordinate (height over ground)
	Lat       float32 // GPS X coordinate
	Lon       float32 // GPS Y coordinate
	Alt       float32 // Global frame altitude
	GroundX   float32 // Ground truth X
	GroundY   float32 // Ground truth Y
	GroundZ   float32 // Ground truth Z
}

func (*ImageTriggered) MsgID

func (self *ImageTriggered) MsgID() uint8

func (*ImageTriggered) MsgName

func (self *ImageTriggered) MsgName() string

func (*ImageTriggered) Pack

func (self *ImageTriggered) Pack(p *Packet) error

func (*ImageTriggered) Unpack

func (self *ImageTriggered) Unpack(p *Packet) error

type LandingTarget

type LandingTarget struct {
	TimeUsec  uint64  // Timestamp (micros since boot or Unix epoch)
	AngleX    float32 // X-axis angular offset (in radians) of the target from the center of the image
	AngleY    float32 // Y-axis angular offset (in radians) of the target from the center of the image
	Distance  float32 // Distance to the target from the vehicle in meters
	SizeX     float32 // Size in radians of target along x-axis
	SizeY     float32 // Size in radians of target along y-axis
	TargetNum uint8   // The ID of the target if multiple targets are present
	Frame     uint8   // MAV_FRAME enum specifying the whether the following feilds are earth-frame, body-frame, etc.
}

The location of a landing area captured from a downward facing camera

func (*LandingTarget) MsgID

func (self *LandingTarget) MsgID() uint8

func (*LandingTarget) MsgName

func (self *LandingTarget) MsgName() string

func (*LandingTarget) Pack

func (self *LandingTarget) Pack(p *Packet) error

func (*LandingTarget) Unpack

func (self *LandingTarget) Unpack(p *Packet) error

type LedControl

type LedControl struct {
	TargetSystem    uint8     // System ID
	TargetComponent uint8     // Component ID
	Instance        uint8     // Instance (LED instance to control or 255 for all LEDs)
	Pattern         uint8     // Pattern (see LED_PATTERN_ENUM)
	CustomLen       uint8     // Custom Byte Length
	CustomBytes     [24]uint8 // Custom Bytes
}

Control vehicle LEDs

func (*LedControl) MsgID

func (self *LedControl) MsgID() uint8

func (*LedControl) MsgName

func (self *LedControl) MsgName() string

func (*LedControl) Pack

func (self *LedControl) Pack(p *Packet) error

func (*LedControl) Unpack

func (self *LedControl) Unpack(p *Packet) error

type LimitsStatus

type LimitsStatus struct {
	LastTrigger   uint32 // time of last breach in milliseconds since boot
	LastAction    uint32 // time of last recovery action in milliseconds since boot
	LastRecovery  uint32 // time of last successful recovery in milliseconds since boot
	LastClear     uint32 // time of last all-clear in milliseconds since boot
	BreachCount   uint16 // number of fence breaches
	LimitsState   uint8  // state of AP_Limits, (see enum LimitState, LIMITS_STATE)
	ModsEnabled   uint8  // AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE)
	ModsRequired  uint8  // AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE)
	ModsTriggered uint8  // AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE)
}

Status of AP_Limits. Sent in extended

status stream when AP_Limits is enabled

func (*LimitsStatus) MsgID

func (self *LimitsStatus) MsgID() uint8

func (*LimitsStatus) MsgName

func (self *LimitsStatus) MsgName() string

func (*LimitsStatus) Pack

func (self *LimitsStatus) Pack(p *Packet) error

func (*LimitsStatus) Unpack

func (self *LimitsStatus) Unpack(p *Packet) error

type LocalPositionNed

type LocalPositionNed struct {
	TimeBootMs uint32  // Timestamp (milliseconds since system boot)
	X          float32 // X Position
	Y          float32 // Y Position
	Z          float32 // Z Position
	Vx         float32 // X Speed
	Vy         float32 // Y Speed
	Vz         float32 // Z Speed
}

The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)

func (*LocalPositionNed) MsgID

func (self *LocalPositionNed) MsgID() uint8

func (*LocalPositionNed) MsgName

func (self *LocalPositionNed) MsgName() string

func (*LocalPositionNed) Pack

func (self *LocalPositionNed) Pack(p *Packet) error

func (*LocalPositionNed) Unpack

func (self *LocalPositionNed) Unpack(p *Packet) error

type LocalPositionNedCov

type LocalPositionNedCov struct {
	TimeUtc       uint64      // Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
	TimeBootMs    uint32      // Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp
	X             float32     // X Position
	Y             float32     // Y Position
	Z             float32     // Z Position
	Vx            float32     // X Speed (m/s)
	Vy            float32     // Y Speed (m/s)
	Vz            float32     // Z Speed (m/s)
	Ax            float32     // X Acceleration (m/s^2)
	Ay            float32     // Y Acceleration (m/s^2)
	Az            float32     // Z Acceleration (m/s^2)
	Covariance    [45]float32 // Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
	EstimatorType uint8       // Class id of the estimator this estimate originated from.
}

The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)

func (*LocalPositionNedCov) MsgID

func (self *LocalPositionNedCov) MsgID() uint8

func (*LocalPositionNedCov) MsgName

func (self *LocalPositionNedCov) MsgName() string

func (*LocalPositionNedCov) Pack

func (self *LocalPositionNedCov) Pack(p *Packet) error

func (*LocalPositionNedCov) Unpack

func (self *LocalPositionNedCov) Unpack(p *Packet) error

type LocalPositionNedSystemGlobalOffset

type LocalPositionNedSystemGlobalOffset struct {
	TimeBootMs uint32  // Timestamp (milliseconds since system boot)
	X          float32 // X Position
	Y          float32 // Y Position
	Z          float32 // Z Position
	Roll       float32 // Roll
	Pitch      float32 // Pitch
	Yaw        float32 // Yaw
}

The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)

func (*LocalPositionNedSystemGlobalOffset) MsgID

func (*LocalPositionNedSystemGlobalOffset) MsgName

func (*LocalPositionNedSystemGlobalOffset) Pack

func (*LocalPositionNedSystemGlobalOffset) Unpack

type LogData

type LogData struct {
	Ofs   uint32    // Offset into the log
	Id    uint16    // Log id (from LOG_ENTRY reply)
	Count uint8     // Number of bytes (zero for end of log)
	Data  [90]uint8 // log data
}

Reply to LOG_REQUEST_DATA

func (*LogData) MsgID

func (self *LogData) MsgID() uint8

func (*LogData) MsgName

func (self *LogData) MsgName() string

func (*LogData) Pack

func (self *LogData) Pack(p *Packet) error

func (*LogData) Unpack

func (self *LogData) Unpack(p *Packet) error

type LogEntry

type LogEntry struct {
	TimeUtc    uint32 // UTC timestamp of log in seconds since 1970, or 0 if not available
	Size       uint32 // Size of the log (may be approximate) in bytes
	Id         uint16 // Log id
	NumLogs    uint16 // Total number of logs
	LastLogNum uint16 // High log number
}

Reply to LOG_REQUEST_LIST

func (*LogEntry) MsgID

func (self *LogEntry) MsgID() uint8

func (*LogEntry) MsgName

func (self *LogEntry) MsgName() string

func (*LogEntry) Pack

func (self *LogEntry) Pack(p *Packet) error

func (*LogEntry) Unpack

func (self *LogEntry) Unpack(p *Packet) error

type LogErase

type LogErase struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Erase all logs

func (*LogErase) MsgID

func (self *LogErase) MsgID() uint8

func (*LogErase) MsgName

func (self *LogErase) MsgName() string

func (*LogErase) Pack

func (self *LogErase) Pack(p *Packet) error

func (*LogErase) Unpack

func (self *LogErase) Unpack(p *Packet) error

type LogRequestData

type LogRequestData struct {
	Ofs             uint32 // Offset into the log
	Count           uint32 // Number of bytes
	Id              uint16 // Log id (from LOG_ENTRY reply)
	TargetSystem    uint8  // System ID
	TargetComponent uint8  // Component ID
}

Request a chunk of a log

func (*LogRequestData) MsgID

func (self *LogRequestData) MsgID() uint8

func (*LogRequestData) MsgName

func (self *LogRequestData) MsgName() string

func (*LogRequestData) Pack

func (self *LogRequestData) Pack(p *Packet) error

func (*LogRequestData) Unpack

func (self *LogRequestData) Unpack(p *Packet) error

type LogRequestEnd

type LogRequestEnd struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Stop log transfer and resume normal logging

func (*LogRequestEnd) MsgID

func (self *LogRequestEnd) MsgID() uint8

func (*LogRequestEnd) MsgName

func (self *LogRequestEnd) MsgName() string

func (*LogRequestEnd) Pack

func (self *LogRequestEnd) Pack(p *Packet) error

func (*LogRequestEnd) Unpack

func (self *LogRequestEnd) Unpack(p *Packet) error

type LogRequestList

type LogRequestList struct {
	Start           uint16 // First log id (0 for first available)
	End             uint16 // Last log id (0xffff for last available)
	TargetSystem    uint8  // System ID
	TargetComponent uint8  // Component ID
}

Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called.

func (*LogRequestList) MsgID

func (self *LogRequestList) MsgID() uint8

func (*LogRequestList) MsgName

func (self *LogRequestList) MsgName() string

func (*LogRequestList) Pack

func (self *LogRequestList) Pack(p *Packet) error

func (*LogRequestList) Unpack

func (self *LogRequestList) Unpack(p *Packet) error

type MagCalProgress

type MagCalProgress struct {
	DirectionX     float32   // Body frame direction vector for display
	DirectionY     float32   // Body frame direction vector for display
	DirectionZ     float32   // Body frame direction vector for display
	CompassId      uint8     // Compass being calibrated
	CalMask        uint8     // Bitmask of compasses being calibrated
	CalStatus      uint8     // Status (see MAG_CAL_STATUS enum)
	Attempt        uint8     // Attempt number
	CompletionPct  uint8     // Completion percentage
	CompletionMask [10]uint8 // Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid)
}

Reports progress of compass calibration.

func (*MagCalProgress) MsgID

func (self *MagCalProgress) MsgID() uint8

func (*MagCalProgress) MsgName

func (self *MagCalProgress) MsgName() string

func (*MagCalProgress) Pack

func (self *MagCalProgress) Pack(p *Packet) error

func (*MagCalProgress) Unpack

func (self *MagCalProgress) Unpack(p *Packet) error

type MagCalReport

type MagCalReport struct {
	Fitness   float32 // RMS milligauss residuals
	OfsX      float32 // X offset
	OfsY      float32 // Y offset
	OfsZ      float32 // Z offset
	DiagX     float32 // X diagonal (matrix 11)
	DiagY     float32 // Y diagonal (matrix 22)
	DiagZ     float32 // Z diagonal (matrix 33)
	OffdiagX  float32 // X off-diagonal (matrix 12 and 21)
	OffdiagY  float32 // Y off-diagonal (matrix 13 and 31)
	OffdiagZ  float32 // Z off-diagonal (matrix 32 and 23)
	CompassId uint8   // Compass being calibrated
	CalMask   uint8   // Bitmask of compasses being calibrated
	CalStatus uint8   // Status (see MAG_CAL_STATUS enum)
	Autosaved uint8   // 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters
}

Reports results of completed compass calibration. Sent until MAG_CAL_ACK received.

func (*MagCalReport) MsgID

func (self *MagCalReport) MsgID() uint8

func (*MagCalReport) MsgName

func (self *MagCalReport) MsgName() string

func (*MagCalReport) Pack

func (self *MagCalReport) Pack(p *Packet) error

func (*MagCalReport) Unpack

func (self *MagCalReport) Unpack(p *Packet) error

type ManualControl

type ManualControl struct {
	X       int16  // X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
	Y       int16  // Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
	Z       int16  // Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle.
	R       int16  // R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
	Buttons uint16 // A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.
	Target  uint8  // The system to be controlled.
}

This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled an buttons are also transmit as boolean values of their

func (*ManualControl) MsgID

func (self *ManualControl) MsgID() uint8

func (*ManualControl) MsgName

func (self *ManualControl) MsgName() string

func (*ManualControl) Pack

func (self *ManualControl) Pack(p *Packet) error

func (*ManualControl) Unpack

func (self *ManualControl) Unpack(p *Packet) error

type ManualSetpoint

type ManualSetpoint struct {
	TimeBootMs           uint32  // Timestamp in milliseconds since system boot
	Roll                 float32 // Desired roll rate in radians per second
	Pitch                float32 // Desired pitch rate in radians per second
	Yaw                  float32 // Desired yaw rate in radians per second
	Thrust               float32 // Collective thrust, normalized to 0 .. 1
	ModeSwitch           uint8   // Flight mode switch position, 0.. 255
	ManualOverrideSwitch uint8   // Override mode switch position, 0.. 255
}

Setpoint in roll, pitch, yaw and thrust from the operator

func (*ManualSetpoint) MsgID

func (self *ManualSetpoint) MsgID() uint8

func (*ManualSetpoint) MsgName

func (self *ManualSetpoint) MsgName() string

func (*ManualSetpoint) Pack

func (self *ManualSetpoint) Pack(p *Packet) error

func (*ManualSetpoint) Unpack

func (self *ManualSetpoint) Unpack(p *Packet) error

type Marker

type Marker struct {
	X     float32 // x position
	Y     float32 // y position
	Z     float32 // z position
	Roll  float32 // roll orientation
	Pitch float32 // pitch orientation
	Yaw   float32 // yaw orientation
	Id    uint16  // ID
}

func (*Marker) MsgID

func (self *Marker) MsgID() uint8

func (*Marker) MsgName

func (self *Marker) MsgName() string

func (*Marker) Pack

func (self *Marker) Pack(p *Packet) error

func (*Marker) Unpack

func (self *Marker) Unpack(p *Packet) error

type Meminfo

type Meminfo struct {
	Brkval  uint16 // heap top
	Freemem uint16 // free memory
}

state of APM memory

func (*Meminfo) MsgID

func (self *Meminfo) MsgID() uint8

func (*Meminfo) MsgName

func (self *Meminfo) MsgName() string

func (*Meminfo) Pack

func (self *Meminfo) Pack(p *Packet) error

func (*Meminfo) Unpack

func (self *Meminfo) Unpack(p *Packet) error

type MemoryVect

type MemoryVect struct {
	Address uint16   // Starting address of the debug variables
	Ver     uint8    // Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
	Type    uint8    // Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
	Value   [32]int8 // Memory contents at specified address
}

Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.

func (*MemoryVect) MsgID

func (self *MemoryVect) MsgID() uint8

func (*MemoryVect) MsgName

func (self *MemoryVect) MsgName() string

func (*MemoryVect) Pack

func (self *MemoryVect) Pack(p *Packet) error

func (*MemoryVect) Unpack

func (self *MemoryVect) Unpack(p *Packet) error

type Message

type Message interface {
	Pack(*Packet) error
	Unpack(*Packet) error
}

basic type for encoding/decoding mavlink messages. use the Pack() and Unpack() routines on specific message types to convert them to/from the Packet type.

type MessageInterval

type MessageInterval struct {
	IntervalUs int32  // The interval between two messages, in microseconds. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.
	MessageId  uint16 // The ID of the requested MAVLink message. v1.0 is limited to 254 messages.
}

This interface replaces DATA_STREAM

func (*MessageInterval) MsgID

func (self *MessageInterval) MsgID() uint8

func (*MessageInterval) MsgName

func (self *MessageInterval) MsgName() string

func (*MessageInterval) Pack

func (self *MessageInterval) Pack(p *Packet) error

func (*MessageInterval) Unpack

func (self *MessageInterval) Unpack(p *Packet) error

type MissionAck

type MissionAck struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
	Type            uint8 // See MAV_MISSION_RESULT enum
}

Ack message during MISSION handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero).

func (*MissionAck) MsgID

func (self *MissionAck) MsgID() uint8

func (*MissionAck) MsgName

func (self *MissionAck) MsgName() string

func (*MissionAck) Pack

func (self *MissionAck) Pack(p *Packet) error

func (*MissionAck) Unpack

func (self *MissionAck) Unpack(p *Packet) error

type MissionClearAll

type MissionClearAll struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Delete all mission items at once.

func (*MissionClearAll) MsgID

func (self *MissionClearAll) MsgID() uint8

func (*MissionClearAll) MsgName

func (self *MissionClearAll) MsgName() string

func (*MissionClearAll) Pack

func (self *MissionClearAll) Pack(p *Packet) error

func (*MissionClearAll) Unpack

func (self *MissionClearAll) Unpack(p *Packet) error

type MissionCount

type MissionCount struct {
	Count           uint16 // Number of mission items in the sequence
	TargetSystem    uint8  // System ID
	TargetComponent uint8  // Component ID
}

This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of MISSIONs.

func (*MissionCount) MsgID

func (self *MissionCount) MsgID() uint8

func (*MissionCount) MsgName

func (self *MissionCount) MsgName() string

func (*MissionCount) Pack

func (self *MissionCount) Pack(p *Packet) error

func (*MissionCount) Unpack

func (self *MissionCount) Unpack(p *Packet) error

type MissionCurrent

type MissionCurrent struct {
	Seq uint16 // Sequence
}

Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item.

func (*MissionCurrent) MsgID

func (self *MissionCurrent) MsgID() uint8

func (*MissionCurrent) MsgName

func (self *MissionCurrent) MsgName() string

func (*MissionCurrent) Pack

func (self *MissionCurrent) Pack(p *Packet) error

func (*MissionCurrent) Unpack

func (self *MissionCurrent) Unpack(p *Packet) error

type MissionItem

type MissionItem struct {
	Param1          float32 // PARAM1, see MAV_CMD enum
	Param2          float32 // PARAM2, see MAV_CMD enum
	Param3          float32 // PARAM3, see MAV_CMD enum
	Param4          float32 // PARAM4, see MAV_CMD enum
	X               float32 // PARAM5 / local: x position, global: latitude
	Y               float32 // PARAM6 / y position: global: longitude
	Z               float32 // PARAM7 / z position: global: altitude (relative or absolute, depending on frame.
	Seq             uint16  // Sequence
	Command         uint16  // The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
	Frame           uint8   // The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
	Current         uint8   // false:0, true:1
	Autocontinue    uint8   // autocontinue to next wp
}

Message encoding a mission item. This message is emitted to announce

the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See also http://qgroundcontrol.org/mavlink/waypoint_protocol.

func (*MissionItem) MsgID

func (self *MissionItem) MsgID() uint8

func (*MissionItem) MsgName

func (self *MissionItem) MsgName() string

func (*MissionItem) Pack

func (self *MissionItem) Pack(p *Packet) error

func (*MissionItem) Unpack

func (self *MissionItem) Unpack(p *Packet) error

type MissionItemInt

type MissionItemInt struct {
	Param1          float32 // PARAM1, see MAV_CMD enum
	Param2          float32 // PARAM2, see MAV_CMD enum
	Param3          float32 // PARAM3, see MAV_CMD enum
	Param4          float32 // PARAM4, see MAV_CMD enum
	X               int32   // PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
	Y               int32   // PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7
	Z               float32 // PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
	Seq             uint16  // Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).
	Command         uint16  // The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
	Frame           uint8   // The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
	Current         uint8   // false:0, true:1
	Autocontinue    uint8   // autocontinue to next wp
}

Message encoding a mission item. This message is emitted to announce

the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See alsohttp://qgroundcontrol.org/mavlink/waypoint_protocol.

func (*MissionItemInt) MsgID

func (self *MissionItemInt) MsgID() uint8

func (*MissionItemInt) MsgName

func (self *MissionItemInt) MsgName() string

func (*MissionItemInt) Pack

func (self *MissionItemInt) Pack(p *Packet) error

func (*MissionItemInt) Unpack

func (self *MissionItemInt) Unpack(p *Packet) error

type MissionItemReached

type MissionItemReached struct {
	Seq uint16 // Sequence
}

A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next MISSION.

func (*MissionItemReached) MsgID

func (self *MissionItemReached) MsgID() uint8

func (*MissionItemReached) MsgName

func (self *MissionItemReached) MsgName() string

func (*MissionItemReached) Pack

func (self *MissionItemReached) Pack(p *Packet) error

func (*MissionItemReached) Unpack

func (self *MissionItemReached) Unpack(p *Packet) error

type MissionRequest

type MissionRequest struct {
	Seq             uint16 // Sequence
	TargetSystem    uint8  // System ID
	TargetComponent uint8  // Component ID
}

Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. http://qgroundcontrol.org/mavlink/waypoint_protocol

func (*MissionRequest) MsgID

func (self *MissionRequest) MsgID() uint8

func (*MissionRequest) MsgName

func (self *MissionRequest) MsgName() string

func (*MissionRequest) Pack

func (self *MissionRequest) Pack(p *Packet) error

func (*MissionRequest) Unpack

func (self *MissionRequest) Unpack(p *Packet) error

type MissionRequestList

type MissionRequestList struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Request the overall list of mission items from the system/component.

func (*MissionRequestList) MsgID

func (self *MissionRequestList) MsgID() uint8

func (*MissionRequestList) MsgName

func (self *MissionRequestList) MsgName() string

func (*MissionRequestList) Pack

func (self *MissionRequestList) Pack(p *Packet) error

func (*MissionRequestList) Unpack

func (self *MissionRequestList) Unpack(p *Packet) error

type MissionRequestPartialList

type MissionRequestPartialList struct {
	StartIndex      int16 // Start index, 0 by default
	EndIndex        int16 // End index, -1 by default (-1: send list to end). Else a valid index of the list
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Request a partial list of mission items from the system/component. http://qgroundcontrol.org/mavlink/waypoint_protocol. If start and end index are the same, just send one waypoint.

func (*MissionRequestPartialList) MsgID

func (self *MissionRequestPartialList) MsgID() uint8

func (*MissionRequestPartialList) MsgName

func (self *MissionRequestPartialList) MsgName() string

func (*MissionRequestPartialList) Pack

func (self *MissionRequestPartialList) Pack(p *Packet) error

func (*MissionRequestPartialList) Unpack

func (self *MissionRequestPartialList) Unpack(p *Packet) error

type MissionSetCurrent

type MissionSetCurrent struct {
	Seq             uint16 // Sequence
	TargetSystem    uint8  // System ID
	TargetComponent uint8  // Component ID
}

Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between).

func (*MissionSetCurrent) MsgID

func (self *MissionSetCurrent) MsgID() uint8

func (*MissionSetCurrent) MsgName

func (self *MissionSetCurrent) MsgName() string

func (*MissionSetCurrent) Pack

func (self *MissionSetCurrent) Pack(p *Packet) error

func (*MissionSetCurrent) Unpack

func (self *MissionSetCurrent) Unpack(p *Packet) error

type MissionWritePartialList

type MissionWritePartialList struct {
	StartIndex      int16 // Start index, 0 by default and smaller / equal to the largest index of the current onboard list.
	EndIndex        int16 // End index, equal or greater than start index.
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!

func (*MissionWritePartialList) MsgID

func (self *MissionWritePartialList) MsgID() uint8

func (*MissionWritePartialList) MsgName

func (self *MissionWritePartialList) MsgName() string

func (*MissionWritePartialList) Pack

func (self *MissionWritePartialList) Pack(p *Packet) error

func (*MissionWritePartialList) Unpack

func (self *MissionWritePartialList) Unpack(p *Packet) error

type MountConfigure

type MountConfigure struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
	MountMode       uint8 // mount operating mode (see MAV_MOUNT_MODE enum)
	StabRoll        uint8 // (1 = yes, 0 = no)
	StabPitch       uint8 // (1 = yes, 0 = no)
	StabYaw         uint8 // (1 = yes, 0 = no)
}

Message to configure a camera mount, directional antenna, etc.

func (*MountConfigure) MsgID

func (self *MountConfigure) MsgID() uint8

func (*MountConfigure) MsgName

func (self *MountConfigure) MsgName() string

func (*MountConfigure) Pack

func (self *MountConfigure) Pack(p *Packet) error

func (*MountConfigure) Unpack

func (self *MountConfigure) Unpack(p *Packet) error

type MountControl

type MountControl struct {
	InputA          int32 // pitch(deg*100) or lat, depending on mount mode
	InputB          int32 // roll(deg*100) or lon depending on mount mode
	InputC          int32 // yaw(deg*100) or alt (in cm) depending on mount mode
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
	SavePosition    uint8 // if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
}

Message to control a camera mount, directional antenna, etc.

func (*MountControl) MsgID

func (self *MountControl) MsgID() uint8

func (*MountControl) MsgName

func (self *MountControl) MsgName() string

func (*MountControl) Pack

func (self *MountControl) Pack(p *Packet) error

func (*MountControl) Unpack

func (self *MountControl) Unpack(p *Packet) error

type MountStatus

type MountStatus struct {
	PointingA       int32 // pitch(deg*100)
	PointingB       int32 // roll(deg*100)
	PointingC       int32 // yaw(deg*100)
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Message with some status from APM to GCS about camera or antenna mount

func (*MountStatus) MsgID

func (self *MountStatus) MsgID() uint8

func (*MountStatus) MsgName

func (self *MountStatus) MsgName() string

func (*MountStatus) Pack

func (self *MountStatus) Pack(p *Packet) error

func (*MountStatus) Unpack

func (self *MountStatus) Unpack(p *Packet) error

type NamedValueFloat

type NamedValueFloat struct {
	TimeBootMs uint32   // Timestamp (milliseconds since system boot)
	Value      float32  // Floating point value
	Name       [10]byte // Name of the debug variable
}

Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.

func (*NamedValueFloat) MsgID

func (self *NamedValueFloat) MsgID() uint8

func (*NamedValueFloat) MsgName

func (self *NamedValueFloat) MsgName() string

func (*NamedValueFloat) Pack

func (self *NamedValueFloat) Pack(p *Packet) error

func (*NamedValueFloat) Unpack

func (self *NamedValueFloat) Unpack(p *Packet) error

type NamedValueInt

type NamedValueInt struct {
	TimeBootMs uint32   // Timestamp (milliseconds since system boot)
	Value      int32    // Signed integer value
	Name       [10]byte // Name of the debug variable
}

Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.

func (*NamedValueInt) MsgID

func (self *NamedValueInt) MsgID() uint8

func (*NamedValueInt) MsgName

func (self *NamedValueInt) MsgName() string

func (*NamedValueInt) Pack

func (self *NamedValueInt) Pack(p *Packet) error

func (*NamedValueInt) Unpack

func (self *NamedValueInt) Unpack(p *Packet) error
type NavControllerOutput struct {
	NavRoll       float32 // Current desired roll in degrees
	NavPitch      float32 // Current desired pitch in degrees
	AltError      float32 // Current altitude error in meters
	AspdError     float32 // Current airspeed error in meters/second
	XtrackError   float32 // Current crosstrack error on x-y plane in meters
	NavBearing    int16   // Current desired heading in degrees
	TargetBearing int16   // Bearing to current MISSION/target in degrees
	WpDist        uint16  // Distance to active MISSION in meters
}

Outputs of the APM navigation controller. The primary use of this message is to check the response and signs of the controller before actual flight and to assist with tuning controller parameters.

func (self *NavControllerOutput) MsgID() uint8
func (self *NavControllerOutput) MsgName() string
func (self *NavControllerOutput) Pack(p *Packet) error
func (self *NavControllerOutput) Unpack(p *Packet) error
type NavFilterBias struct {
	Usec   uint64  // Timestamp (microseconds)
	Accel0 float32 // b_f[0]
	Accel1 float32 // b_f[1]
	Accel2 float32 // b_f[2]
	Gyro0  float32 // b_f[0]
	Gyro1  float32 // b_f[1]
	Gyro2  float32 // b_f[2]
}

Accelerometer and Gyro biases from the navigation filter

func (self *NavFilterBias) MsgID() uint8
func (self *NavFilterBias) MsgName() string
func (self *NavFilterBias) Pack(p *Packet) error
func (self *NavFilterBias) Unpack(p *Packet) error

type OnboardHealth

type OnboardHealth struct {
	Uptime         uint32  // Uptime of system
	RamTotal       float32 // RAM size in GiB
	SwapTotal      float32 // Swap size in GiB
	DiskTotal      float32 // Disk total in GiB
	Temp           float32 // Temperature
	Voltage        float32 // Supply voltage V
	NetworkLoadIn  float32 // Network load inbound KiB/s
	NetworkLoadOut float32 // Network load outbound in KiB/s
	CpuFreq        uint16  // CPU frequency
	CpuLoad        uint8   // CPU load in percent
	RamUsage       uint8   // RAM usage in percent
	SwapUsage      uint8   // Swap usage in percent
	DiskHealth     int8    // Disk health (-1: N/A, 0: ERR, 1: RO, 2: RW)
	DiskUsage      uint8   // Disk usage in percent
}

func (*OnboardHealth) MsgID

func (self *OnboardHealth) MsgID() uint8

func (*OnboardHealth) MsgName

func (self *OnboardHealth) MsgName() string

func (*OnboardHealth) Pack

func (self *OnboardHealth) Pack(p *Packet) error

func (*OnboardHealth) Unpack

func (self *OnboardHealth) Unpack(p *Packet) error

type OpticalFlow

type OpticalFlow struct {
	TimeUsec       uint64  // Timestamp (UNIX)
	FlowCompMX     float32 // Flow in meters in x-sensor direction, angular-speed compensated
	FlowCompMY     float32 // Flow in meters in y-sensor direction, angular-speed compensated
	GroundDistance float32 // Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
	FlowX          int16   // Flow in pixels * 10 in x-sensor direction (dezi-pixels)
	FlowY          int16   // Flow in pixels * 10 in y-sensor direction (dezi-pixels)
	SensorId       uint8   // Sensor ID
	Quality        uint8   // Optical flow quality / confidence. 0: bad, 255: maximum quality
}

Optical flow from a flow sensor (e.g. optical mouse sensor)

func (*OpticalFlow) MsgID

func (self *OpticalFlow) MsgID() uint8

func (*OpticalFlow) MsgName

func (self *OpticalFlow) MsgName() string

func (*OpticalFlow) Pack

func (self *OpticalFlow) Pack(p *Packet) error

func (*OpticalFlow) Unpack

func (self *OpticalFlow) Unpack(p *Packet) error

type OpticalFlowRad

type OpticalFlowRad struct {
	TimeUsec            uint64  // Timestamp (microseconds, synced to UNIX time or since system boot)
	IntegrationTimeUs   uint32  // Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
	IntegratedX         float32 // Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
	IntegratedY         float32 // Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
	IntegratedXgyro     float32 // RH rotation around X axis (rad)
	IntegratedYgyro     float32 // RH rotation around Y axis (rad)
	IntegratedZgyro     float32 // RH rotation around Z axis (rad)
	TimeDeltaDistanceUs uint32  // Time in microseconds since the distance was sampled.
	Distance            float32 // Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
	Temperature         int16   // Temperature * 100 in centi-degrees Celsius
	SensorId            uint8   // Sensor ID
	Quality             uint8   // Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
}

Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor)

func (*OpticalFlowRad) MsgID

func (self *OpticalFlowRad) MsgID() uint8

func (*OpticalFlowRad) MsgName

func (self *OpticalFlowRad) MsgName() string

func (*OpticalFlowRad) Pack

func (self *OpticalFlowRad) Pack(p *Packet) error

func (*OpticalFlowRad) Unpack

func (self *OpticalFlowRad) Unpack(p *Packet) error

type Packet

type Packet struct {
	SeqID    uint8 // Sequence of packet
	SysID    uint8 // ID of message sender system/aircraft
	CompID   uint8 // ID of the message sender component
	MsgID    uint8 // ID of message in payload
	Payload  []byte
	Checksum uint16
}

wire type for encoding/decoding mavlink messages. use the ToPacket() and FromPacket() routines on specific message types to convert them to/from the Message type.

type ParamMapRc

type ParamMapRc struct {
	ParamValue0             float32  // Initial parameter value
	Scale                   float32  // Scale, maps the RC range [-1, 1] to a parameter value
	ParamValueMin           float32  // Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)
	ParamValueMax           float32  // Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)
	ParamIndex              int16    // Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.
	TargetSystem            uint8    // System ID
	TargetComponent         uint8    // Component ID
	ParamId                 [16]byte // Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
	ParameterRcChannelIndex uint8    // Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.
}

Bind a RC channel to a parameter. The parameter should change accoding to the RC channel value.

func (*ParamMapRc) MsgID

func (self *ParamMapRc) MsgID() uint8

func (*ParamMapRc) MsgName

func (self *ParamMapRc) MsgName() string

func (*ParamMapRc) Pack

func (self *ParamMapRc) Pack(p *Packet) error

func (*ParamMapRc) Unpack

func (self *ParamMapRc) Unpack(p *Packet) error

type ParamRequestList

type ParamRequestList struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Request all parameters of this component. After his request, all parameters are emitted.

func (*ParamRequestList) MsgID

func (self *ParamRequestList) MsgID() uint8

func (*ParamRequestList) MsgName

func (self *ParamRequestList) MsgName() string

func (*ParamRequestList) Pack

func (self *ParamRequestList) Pack(p *Packet) error

func (*ParamRequestList) Unpack

func (self *ParamRequestList) Unpack(p *Packet) error

type ParamRequestRead

type ParamRequestRead struct {
	ParamIndex      int16    // Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
	TargetSystem    uint8    // System ID
	TargetComponent uint8    // Component ID
	ParamId         [16]byte // Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
}

Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code.

func (*ParamRequestRead) MsgID

func (self *ParamRequestRead) MsgID() uint8

func (*ParamRequestRead) MsgName

func (self *ParamRequestRead) MsgName() string

func (*ParamRequestRead) Pack

func (self *ParamRequestRead) Pack(p *Packet) error

func (*ParamRequestRead) Unpack

func (self *ParamRequestRead) Unpack(p *Packet) error

type ParamSet

type ParamSet struct {
	ParamValue      float32  // Onboard parameter value
	TargetSystem    uint8    // System ID
	TargetComponent uint8    // Component ID
	ParamId         [16]byte // Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
	ParamType       uint8    // Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
}

Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message.

func (*ParamSet) MsgID

func (self *ParamSet) MsgID() uint8

func (*ParamSet) MsgName

func (self *ParamSet) MsgName() string

func (*ParamSet) Pack

func (self *ParamSet) Pack(p *Packet) error

func (*ParamSet) Unpack

func (self *ParamSet) Unpack(p *Packet) error

type ParamValue

type ParamValue struct {
	ParamValue float32  // Onboard parameter value
	ParamCount uint16   // Total number of onboard parameters
	ParamIndex uint16   // Index of this onboard parameter
	ParamId    [16]byte // Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
	ParamType  uint8    // Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
}

Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout.

func (*ParamValue) MsgID

func (self *ParamValue) MsgID() uint8

func (*ParamValue) MsgName

func (self *ParamValue) MsgName() string

func (*ParamValue) Pack

func (self *ParamValue) Pack(p *Packet) error

func (*ParamValue) Unpack

func (self *ParamValue) Unpack(p *Packet) error

type PatternDetected

type PatternDetected struct {
	Confidence float32   // Confidence of detection
	Type       uint8     // 0: Pattern, 1: Letter
	File       [100]byte // Pattern file name
	Detected   uint8     // Accepted as true detection, 0 no, 1 yes
}

func (*PatternDetected) MsgID

func (self *PatternDetected) MsgID() uint8

func (*PatternDetected) MsgName

func (self *PatternDetected) MsgName() string

func (*PatternDetected) Pack

func (self *PatternDetected) Pack(p *Packet) error

func (*PatternDetected) Unpack

func (self *PatternDetected) Unpack(p *Packet) error

type PidTuning

type PidTuning struct {
	Desired  float32 // desired rate (degrees/s)
	Achieved float32 // achieved rate (degrees/s)
	Ff       float32 // FF component
	P        float32 // P component
	I        float32 // I component
	D        float32 // D component
	Axis     uint8   // axis
}

PID tuning information

func (*PidTuning) MsgID

func (self *PidTuning) MsgID() uint8

func (*PidTuning) MsgName

func (self *PidTuning) MsgName() string

func (*PidTuning) Pack

func (self *PidTuning) Pack(p *Packet) error

func (*PidTuning) Unpack

func (self *PidTuning) Unpack(p *Packet) error

type Ping

type Ping struct {
	TimeUsec        uint64 // Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
	Seq             uint32 // PING sequence
	TargetSystem    uint8  // 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
	TargetComponent uint8  // 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
}

A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections.

func (*Ping) MsgID

func (self *Ping) MsgID() uint8

func (*Ping) MsgName

func (self *Ping) MsgName() string

func (*Ping) Pack

func (self *Ping) Pack(p *Packet) error

func (*Ping) Unpack

func (self *Ping) Unpack(p *Packet) error

type PointOfInterest

type PointOfInterest struct {
	X                float32  // X Position
	Y                float32  // Y Position
	Z                float32  // Z Position
	Timeout          uint16   // 0: no timeout, >1: timeout in seconds
	Type             uint8    // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
	Color            uint8    // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
	CoordinateSystem uint8    // 0: global, 1:local
	Name             [26]byte // POI name
}

Notifies the operator about a point of interest (POI). This can be anything detected by the

system. This generic message is intented to help interfacing to generic visualizations and to display
the POI on a map.

func (*PointOfInterest) MsgID

func (self *PointOfInterest) MsgID() uint8

func (*PointOfInterest) MsgName

func (self *PointOfInterest) MsgName() string

func (*PointOfInterest) Pack

func (self *PointOfInterest) Pack(p *Packet) error

func (*PointOfInterest) Unpack

func (self *PointOfInterest) Unpack(p *Packet) error

type PointOfInterestConnection

type PointOfInterestConnection struct {
	Xp1              float32  // X1 Position
	Yp1              float32  // Y1 Position
	Zp1              float32  // Z1 Position
	Xp2              float32  // X2 Position
	Yp2              float32  // Y2 Position
	Zp2              float32  // Z2 Position
	Timeout          uint16   // 0: no timeout, >1: timeout in seconds
	Type             uint8    // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
	Color            uint8    // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
	CoordinateSystem uint8    // 0: global, 1:local
	Name             [26]byte // POI connection name
}

Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the

system. This generic message is intented to help interfacing to generic visualizations and to display
the POI on a map.

func (*PointOfInterestConnection) MsgID

func (self *PointOfInterestConnection) MsgID() uint8

func (*PointOfInterestConnection) MsgName

func (self *PointOfInterestConnection) MsgName() string

func (*PointOfInterestConnection) Pack

func (self *PointOfInterestConnection) Pack(p *Packet) error

func (*PointOfInterestConnection) Unpack

func (self *PointOfInterestConnection) Unpack(p *Packet) error

type PositionControlSetpoint

type PositionControlSetpoint struct {
	X   float32 // x position
	Y   float32 // y position
	Z   float32 // z position
	Yaw float32 // yaw orientation in radians, 0 = NORTH
	Id  uint16  // ID of waypoint, 0 for plain position
}

func (*PositionControlSetpoint) MsgID

func (self *PositionControlSetpoint) MsgID() uint8

func (*PositionControlSetpoint) MsgName

func (self *PositionControlSetpoint) MsgName() string

func (*PositionControlSetpoint) Pack

func (self *PositionControlSetpoint) Pack(p *Packet) error

func (*PositionControlSetpoint) Unpack

func (self *PositionControlSetpoint) Unpack(p *Packet) error

type PositionTargetGlobalInt

type PositionTargetGlobalInt struct {
	TimeBootMs      uint32  // 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.
	LatInt          int32   // X Position in WGS84 frame in 1e7 * meters
	LonInt          int32   // Y Position in WGS84 frame in 1e7 * meters
	Alt             float32 // Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
	Vx              float32 // X velocity in NED frame in meter / s
	Vy              float32 // Y velocity in NED frame in meter / s
	Vz              float32 // Z velocity in NED frame in meter / s
	Afx             float32 // X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afy             float32 // Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afz             float32 // Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Yaw             float32 // yaw setpoint in rad
	YawRate         float32 // yaw rate setpoint in rad/s
	TypeMask        uint16  // 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. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. 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: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
	CoordinateFrame uint8   // Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
}

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

func (*PositionTargetGlobalInt) MsgID

func (self *PositionTargetGlobalInt) MsgID() uint8

func (*PositionTargetGlobalInt) MsgName

func (self *PositionTargetGlobalInt) MsgName() string

func (*PositionTargetGlobalInt) Pack

func (self *PositionTargetGlobalInt) Pack(p *Packet) error

func (*PositionTargetGlobalInt) Unpack

func (self *PositionTargetGlobalInt) Unpack(p *Packet) error

type PositionTargetLocalNed

type PositionTargetLocalNed struct {
	TimeBootMs      uint32  // Timestamp in milliseconds since system boot
	X               float32 // X Position in NED frame in meters
	Y               float32 // Y Position in NED frame in meters
	Z               float32 // Z Position in NED frame in meters (note, altitude is negative in NED)
	Vx              float32 // X velocity in NED frame in meter / s
	Vy              float32 // Y velocity in NED frame in meter / s
	Vz              float32 // Z velocity in NED frame in meter / s
	Afx             float32 // X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afy             float32 // Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afz             float32 // Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Yaw             float32 // yaw setpoint in rad
	YawRate         float32 // yaw rate setpoint in rad/s
	TypeMask        uint16  // 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. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. 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: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
	CoordinateFrame uint8   // Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
}

Set vehicle position, velocity and acceleration setpoint in local frame.

func (*PositionTargetLocalNed) MsgID

func (self *PositionTargetLocalNed) MsgID() uint8

func (*PositionTargetLocalNed) MsgName

func (self *PositionTargetLocalNed) MsgName() string

func (*PositionTargetLocalNed) Pack

func (self *PositionTargetLocalNed) Pack(p *Packet) error

func (*PositionTargetLocalNed) Unpack

func (self *PositionTargetLocalNed) Unpack(p *Packet) error

type PowerStatus

type PowerStatus struct {
	Vcc    uint16 // 5V rail voltage in millivolts
	Vservo uint16 // servo rail voltage in millivolts
	Flags  uint16 // power supply status flags (see MAV_POWER_STATUS enum)
}

Power supply status

func (*PowerStatus) MsgID

func (self *PowerStatus) MsgID() uint8

func (*PowerStatus) MsgName

func (self *PowerStatus) MsgName() string

func (*PowerStatus) Pack

func (self *PowerStatus) Pack(p *Packet) error

func (*PowerStatus) Unpack

func (self *PowerStatus) Unpack(p *Packet) error

type Radio

type Radio struct {
	Rxerrors uint16 // receive errors
	Fixed    uint16 // count of error corrected packets
	Rssi     uint8  // local signal strength
	Remrssi  uint8  // remote signal strength
	Txbuf    uint8  // how full the tx buffer is as a percentage
	Noise    uint8  // background noise level
	Remnoise uint8  // remote background noise level
}

Status generated by radio

func (*Radio) MsgID

func (self *Radio) MsgID() uint8

func (*Radio) MsgName

func (self *Radio) MsgName() string

func (*Radio) Pack

func (self *Radio) Pack(p *Packet) error

func (*Radio) Unpack

func (self *Radio) Unpack(p *Packet) error

type RadioCalibration

type RadioCalibration struct {
	Aileron  [3]uint16 // Aileron setpoints: left, center, right
	Elevator [3]uint16 // Elevator setpoints: nose down, center, nose up
	Rudder   [3]uint16 // Rudder setpoints: nose left, center, nose right
	Gyro     [2]uint16 // Tail gyro mode/gain setpoints: heading hold, rate mode
	Pitch    [5]uint16 // Pitch curve setpoints (every 25%)
	Throttle [5]uint16 // Throttle curve setpoints (every 25%)
}

Complete set of calibration parameters for the radio

func (*RadioCalibration) MsgID

func (self *RadioCalibration) MsgID() uint8

func (*RadioCalibration) MsgName

func (self *RadioCalibration) MsgName() string

func (*RadioCalibration) Pack

func (self *RadioCalibration) Pack(p *Packet) error

func (*RadioCalibration) Unpack

func (self *RadioCalibration) Unpack(p *Packet) error

type RadioStatus

type RadioStatus struct {
	Rxerrors uint16 // Receive errors
	Fixed    uint16 // Count of error corrected packets
	Rssi     uint8  // Local signal strength
	Remrssi  uint8  // Remote signal strength
	Txbuf    uint8  // Remaining free buffer space in percent.
	Noise    uint8  // Background noise level
	Remnoise uint8  // Remote background noise level
}

Status generated by radio and injected into MAVLink stream.

func (*RadioStatus) MsgID

func (self *RadioStatus) MsgID() uint8

func (*RadioStatus) MsgName

func (self *RadioStatus) MsgName() string

func (*RadioStatus) Pack

func (self *RadioStatus) Pack(p *Packet) error

func (*RadioStatus) Unpack

func (self *RadioStatus) Unpack(p *Packet) error

type RallyFetchPoint

type RallyFetchPoint struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
	Idx             uint8 // point index (first point is 0)
}

Request a current rally point from MAV. MAV should respond with a RALLY_POINT message. MAV should not respond if the request is invalid.

func (*RallyFetchPoint) MsgID

func (self *RallyFetchPoint) MsgID() uint8

func (*RallyFetchPoint) MsgName

func (self *RallyFetchPoint) MsgName() string

func (*RallyFetchPoint) Pack

func (self *RallyFetchPoint) Pack(p *Packet) error

func (*RallyFetchPoint) Unpack

func (self *RallyFetchPoint) Unpack(p *Packet) error

type RallyPoint

type RallyPoint struct {
	Lat             int32  // Latitude of point in degrees * 1E7
	Lng             int32  // Longitude of point in degrees * 1E7
	Alt             int16  // Transit / loiter altitude in meters relative to home
	BreakAlt        int16  // Break altitude in meters relative to home
	LandDir         uint16 // Heading to aim for when landing. In centi-degrees.
	TargetSystem    uint8  // System ID
	TargetComponent uint8  // Component ID
	Idx             uint8  // point index (first point is 0)
	Count           uint8  // total number of points (for sanity checking)
	Flags           uint8  // See RALLY_FLAGS enum for definition of the bitmask.
}

A rally point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS

func (*RallyPoint) MsgID

func (self *RallyPoint) MsgID() uint8

func (*RallyPoint) MsgName

func (self *RallyPoint) MsgName() string

func (*RallyPoint) Pack

func (self *RallyPoint) Pack(p *Packet) error

func (*RallyPoint) Unpack

func (self *RallyPoint) Unpack(p *Packet) error

type Rangefinder

type Rangefinder struct {
	Distance float32 // distance in meters
	Voltage  float32 // raw voltage if available, zero otherwise
}

Rangefinder reporting

func (*Rangefinder) MsgID

func (self *Rangefinder) MsgID() uint8

func (*Rangefinder) MsgName

func (self *Rangefinder) MsgName() string

func (*Rangefinder) Pack

func (self *Rangefinder) Pack(p *Packet) error

func (*Rangefinder) Unpack

func (self *Rangefinder) Unpack(p *Packet) error

type RawAux

type RawAux struct {
	Baro int32  // Barometric pressure (hecto Pascal)
	Adc1 uint16 // ADC1 (J405 ADC3, LPC2148 AD0.6)
	Adc2 uint16 // ADC2 (J405 ADC5, LPC2148 AD0.2)
	Adc3 uint16 // ADC3 (J405 ADC6, LPC2148 AD0.1)
	Adc4 uint16 // ADC4 (J405 ADC7, LPC2148 AD1.3)
	Vbat uint16 // Battery voltage
	Temp int16  // Temperature (degrees celcius)
}

func (*RawAux) MsgID

func (self *RawAux) MsgID() uint8

func (*RawAux) MsgName

func (self *RawAux) MsgName() string

func (*RawAux) Pack

func (self *RawAux) Pack(p *Packet) error

func (*RawAux) Unpack

func (self *RawAux) Unpack(p *Packet) error

type RawImu

type RawImu struct {
	TimeUsec uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	Xacc     int16  // X acceleration (raw)
	Yacc     int16  // Y acceleration (raw)
	Zacc     int16  // Z acceleration (raw)
	Xgyro    int16  // Angular speed around X axis (raw)
	Ygyro    int16  // Angular speed around Y axis (raw)
	Zgyro    int16  // Angular speed around Z axis (raw)
	Xmag     int16  // X Magnetic field (raw)
	Ymag     int16  // Y Magnetic field (raw)
	Zmag     int16  // Z Magnetic field (raw)
}

The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging.

func (*RawImu) MsgID

func (self *RawImu) MsgID() uint8

func (*RawImu) MsgName

func (self *RawImu) MsgName() string

func (*RawImu) Pack

func (self *RawImu) Pack(p *Packet) error

func (*RawImu) Unpack

func (self *RawImu) Unpack(p *Packet) error

type RawPressure

type RawPressure struct {
	TimeUsec    uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	PressAbs    int16  // Absolute pressure (raw)
	PressDiff1  int16  // Differential pressure 1 (raw)
	PressDiff2  int16  // Differential pressure 2 (raw)
	Temperature int16  // Raw Temperature measurement (raw)
}

The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values.

func (*RawPressure) MsgID

func (self *RawPressure) MsgID() uint8

func (*RawPressure) MsgName

func (self *RawPressure) MsgName() string

func (*RawPressure) Pack

func (self *RawPressure) Pack(p *Packet) error

func (*RawPressure) Unpack

func (self *RawPressure) Unpack(p *Packet) error

type RcChannels

type RcChannels struct {
	TimeBootMs uint32 // Timestamp (milliseconds since system boot)
	Chan1Raw   uint16 // RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan2Raw   uint16 // RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan3Raw   uint16 // RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan4Raw   uint16 // RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan5Raw   uint16 // RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan6Raw   uint16 // RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan7Raw   uint16 // RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan8Raw   uint16 // RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan9Raw   uint16 // RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan10Raw  uint16 // RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan11Raw  uint16 // RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan12Raw  uint16 // RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan13Raw  uint16 // RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan14Raw  uint16 // RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan15Raw  uint16 // RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan16Raw  uint16 // RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan17Raw  uint16 // RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan18Raw  uint16 // RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chancount  uint8  // Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
	Rssi       uint8  // Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
}

The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.

func (*RcChannels) MsgID

func (self *RcChannels) MsgID() uint8

func (*RcChannels) MsgName

func (self *RcChannels) MsgName() string

func (*RcChannels) Pack

func (self *RcChannels) Pack(p *Packet) error

func (*RcChannels) Unpack

func (self *RcChannels) Unpack(p *Packet) error

type RcChannelsOverride

type RcChannelsOverride struct {
	Chan1Raw        uint16 // RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.
	Chan2Raw        uint16 // RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.
	Chan3Raw        uint16 // RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.
	Chan4Raw        uint16 // RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.
	Chan5Raw        uint16 // RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.
	Chan6Raw        uint16 // RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.
	Chan7Raw        uint16 // RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.
	Chan8Raw        uint16 // RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.
	TargetSystem    uint8  // System ID
	TargetComponent uint8  // Component ID
}

The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of UINT16_MAX means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.

func (*RcChannelsOverride) MsgID

func (self *RcChannelsOverride) MsgID() uint8

func (*RcChannelsOverride) MsgName

func (self *RcChannelsOverride) MsgName() string

func (*RcChannelsOverride) Pack

func (self *RcChannelsOverride) Pack(p *Packet) error

func (*RcChannelsOverride) Unpack

func (self *RcChannelsOverride) Unpack(p *Packet) error

type RcChannelsRaw

type RcChannelsRaw struct {
	TimeBootMs uint32 // Timestamp (milliseconds since system boot)
	Chan1Raw   uint16 // RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan2Raw   uint16 // RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan3Raw   uint16 // RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan4Raw   uint16 // RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan5Raw   uint16 // RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan6Raw   uint16 // RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan7Raw   uint16 // RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Chan8Raw   uint16 // RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
	Port       uint8  // Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
	Rssi       uint8  // Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
}

The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.

func (*RcChannelsRaw) MsgID

func (self *RcChannelsRaw) MsgID() uint8

func (*RcChannelsRaw) MsgName

func (self *RcChannelsRaw) MsgName() string

func (*RcChannelsRaw) Pack

func (self *RcChannelsRaw) Pack(p *Packet) error

func (*RcChannelsRaw) Unpack

func (self *RcChannelsRaw) Unpack(p *Packet) error

type RcChannelsScaled

type RcChannelsScaled struct {
	TimeBootMs  uint32 // Timestamp (milliseconds since system boot)
	Chan1Scaled int16  // RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
	Chan2Scaled int16  // RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
	Chan3Scaled int16  // RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
	Chan4Scaled int16  // RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
	Chan5Scaled int16  // RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
	Chan6Scaled int16  // RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
	Chan7Scaled int16  // RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
	Chan8Scaled int16  // RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
	Port        uint8  // Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
	Rssi        uint8  // Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
}

The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX.

func (*RcChannelsScaled) MsgID

func (self *RcChannelsScaled) MsgID() uint8

func (*RcChannelsScaled) MsgName

func (self *RcChannelsScaled) MsgName() string

func (*RcChannelsScaled) Pack

func (self *RcChannelsScaled) Pack(p *Packet) error

func (*RcChannelsScaled) Unpack

func (self *RcChannelsScaled) Unpack(p *Packet) error

type RequestDataStream

type RequestDataStream struct {
	ReqMessageRate  uint16 // The requested message rate
	TargetSystem    uint8  // The target requested to send the message stream.
	TargetComponent uint8  // The target requested to send the message stream.
	ReqStreamId     uint8  // The ID of the requested data stream
	StartStop       uint8  // 1 to start sending, 0 to stop sending.
}

THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD.

func (*RequestDataStream) MsgID

func (self *RequestDataStream) MsgID() uint8

func (*RequestDataStream) MsgName

func (self *RequestDataStream) MsgName() string

func (*RequestDataStream) Pack

func (self *RequestDataStream) Pack(p *Packet) error

func (*RequestDataStream) Unpack

func (self *RequestDataStream) Unpack(p *Packet) error

type ResourceRequest

type ResourceRequest struct {
	RequestId    uint8      // Request ID. This ID should be re-used when sending back URI contents
	UriType      uint8      // The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary
	Uri          [120]uint8 // The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)
	TransferType uint8      // The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream.
	Storage      [120]uint8 // The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP).
}

The autopilot is requesting a resource (file, binary, other type of data)

func (*ResourceRequest) MsgID

func (self *ResourceRequest) MsgID() uint8

func (*ResourceRequest) MsgName

func (self *ResourceRequest) MsgName() string

func (*ResourceRequest) Pack

func (self *ResourceRequest) Pack(p *Packet) error

func (*ResourceRequest) Unpack

func (self *ResourceRequest) Unpack(p *Packet) error

type Rpm

type Rpm struct {
	Rpm1 float32 // RPM Sensor1
	Rpm2 float32 // RPM Sensor2
}

RPM sensor output

func (*Rpm) MsgID

func (self *Rpm) MsgID() uint8

func (*Rpm) MsgName

func (self *Rpm) MsgName() string

func (*Rpm) Pack

func (self *Rpm) Pack(p *Packet) error

func (*Rpm) Unpack

func (self *Rpm) Unpack(p *Packet) error

type SafetyAllowedArea

type SafetyAllowedArea struct {
	P1x   float32 // x position 1 / Latitude 1
	P1y   float32 // y position 1 / Longitude 1
	P1z   float32 // z position 1 / Altitude 1
	P2x   float32 // x position 2 / Latitude 2
	P2y   float32 // y position 2 / Longitude 2
	P2z   float32 // z position 2 / Altitude 2
	Frame uint8   // Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
}

Read out the safety zone the MAV currently assumes.

func (*SafetyAllowedArea) MsgID

func (self *SafetyAllowedArea) MsgID() uint8

func (*SafetyAllowedArea) MsgName

func (self *SafetyAllowedArea) MsgName() string

func (*SafetyAllowedArea) Pack

func (self *SafetyAllowedArea) Pack(p *Packet) error

func (*SafetyAllowedArea) Unpack

func (self *SafetyAllowedArea) Unpack(p *Packet) error

type SafetySetAllowedArea

type SafetySetAllowedArea struct {
	P1x             float32 // x position 1 / Latitude 1
	P1y             float32 // y position 1 / Longitude 1
	P1z             float32 // z position 1 / Altitude 1
	P2x             float32 // x position 2 / Latitude 2
	P2y             float32 // y position 2 / Longitude 2
	P2z             float32 // z position 2 / Altitude 2
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
	Frame           uint8   // Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
}

Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/MISSIONs to accept and which to reject. Safety areas are often enforced by national or competition regulations.

func (*SafetySetAllowedArea) MsgID

func (self *SafetySetAllowedArea) MsgID() uint8

func (*SafetySetAllowedArea) MsgName

func (self *SafetySetAllowedArea) MsgName() string

func (*SafetySetAllowedArea) Pack

func (self *SafetySetAllowedArea) Pack(p *Packet) error

func (*SafetySetAllowedArea) Unpack

func (self *SafetySetAllowedArea) Unpack(p *Packet) error

type ScaledImu

type ScaledImu struct {
	TimeBootMs uint32 // Timestamp (milliseconds since system boot)
	Xacc       int16  // X acceleration (mg)
	Yacc       int16  // Y acceleration (mg)
	Zacc       int16  // Z acceleration (mg)
	Xgyro      int16  // Angular speed around X axis (millirad /sec)
	Ygyro      int16  // Angular speed around Y axis (millirad /sec)
	Zgyro      int16  // Angular speed around Z axis (millirad /sec)
	Xmag       int16  // X Magnetic field (milli tesla)
	Ymag       int16  // Y Magnetic field (milli tesla)
	Zmag       int16  // Z Magnetic field (milli tesla)
}

The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units

func (*ScaledImu) MsgID

func (self *ScaledImu) MsgID() uint8

func (*ScaledImu) MsgName

func (self *ScaledImu) MsgName() string

func (*ScaledImu) Pack

func (self *ScaledImu) Pack(p *Packet) error

func (*ScaledImu) Unpack

func (self *ScaledImu) Unpack(p *Packet) error

type ScaledImu2

type ScaledImu2 struct {
	TimeBootMs uint32 // Timestamp (milliseconds since system boot)
	Xacc       int16  // X acceleration (mg)
	Yacc       int16  // Y acceleration (mg)
	Zacc       int16  // Z acceleration (mg)
	Xgyro      int16  // Angular speed around X axis (millirad /sec)
	Ygyro      int16  // Angular speed around Y axis (millirad /sec)
	Zgyro      int16  // Angular speed around Z axis (millirad /sec)
	Xmag       int16  // X Magnetic field (milli tesla)
	Ymag       int16  // Y Magnetic field (milli tesla)
	Zmag       int16  // Z Magnetic field (milli tesla)
}

The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units

func (*ScaledImu2) MsgID

func (self *ScaledImu2) MsgID() uint8

func (*ScaledImu2) MsgName

func (self *ScaledImu2) MsgName() string

func (*ScaledImu2) Pack

func (self *ScaledImu2) Pack(p *Packet) error

func (*ScaledImu2) Unpack

func (self *ScaledImu2) Unpack(p *Packet) error

type ScaledImu3

type ScaledImu3 struct {
	TimeBootMs uint32 // Timestamp (milliseconds since system boot)
	Xacc       int16  // X acceleration (mg)
	Yacc       int16  // Y acceleration (mg)
	Zacc       int16  // Z acceleration (mg)
	Xgyro      int16  // Angular speed around X axis (millirad /sec)
	Ygyro      int16  // Angular speed around Y axis (millirad /sec)
	Zgyro      int16  // Angular speed around Z axis (millirad /sec)
	Xmag       int16  // X Magnetic field (milli tesla)
	Ymag       int16  // Y Magnetic field (milli tesla)
	Zmag       int16  // Z Magnetic field (milli tesla)
}

The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units

func (*ScaledImu3) MsgID

func (self *ScaledImu3) MsgID() uint8

func (*ScaledImu3) MsgName

func (self *ScaledImu3) MsgName() string

func (*ScaledImu3) Pack

func (self *ScaledImu3) Pack(p *Packet) error

func (*ScaledImu3) Unpack

func (self *ScaledImu3) Unpack(p *Packet) error

type ScaledPressure

type ScaledPressure struct {
	TimeBootMs  uint32  // Timestamp (milliseconds since system boot)
	PressAbs    float32 // Absolute pressure (hectopascal)
	PressDiff   float32 // Differential pressure 1 (hectopascal)
	Temperature int16   // Temperature measurement (0.01 degrees celsius)
}

The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.

func (*ScaledPressure) MsgID

func (self *ScaledPressure) MsgID() uint8

func (*ScaledPressure) MsgName

func (self *ScaledPressure) MsgName() string

func (*ScaledPressure) Pack

func (self *ScaledPressure) Pack(p *Packet) error

func (*ScaledPressure) Unpack

func (self *ScaledPressure) Unpack(p *Packet) error

type ScaledPressure2

type ScaledPressure2 struct {
	TimeBootMs  uint32  // Timestamp (milliseconds since system boot)
	PressAbs    float32 // Absolute pressure (hectopascal)
	PressDiff   float32 // Differential pressure 1 (hectopascal)
	Temperature int16   // Temperature measurement (0.01 degrees celsius)
}

Barometer readings for 2nd barometer

func (*ScaledPressure2) MsgID

func (self *ScaledPressure2) MsgID() uint8

func (*ScaledPressure2) MsgName

func (self *ScaledPressure2) MsgName() string

func (*ScaledPressure2) Pack

func (self *ScaledPressure2) Pack(p *Packet) error

func (*ScaledPressure2) Unpack

func (self *ScaledPressure2) Unpack(p *Packet) error

type ScaledPressure3

type ScaledPressure3 struct {
	TimeBootMs  uint32  // Timestamp (milliseconds since system boot)
	PressAbs    float32 // Absolute pressure (hectopascal)
	PressDiff   float32 // Differential pressure 1 (hectopascal)
	Temperature int16   // Temperature measurement (0.01 degrees celsius)
}

Barometer readings for 3rd barometer

func (*ScaledPressure3) MsgID

func (self *ScaledPressure3) MsgID() uint8

func (*ScaledPressure3) MsgName

func (self *ScaledPressure3) MsgName() string

func (*ScaledPressure3) Pack

func (self *ScaledPressure3) Pack(p *Packet) error

func (*ScaledPressure3) Unpack

func (self *ScaledPressure3) Unpack(p *Packet) error

type SensAtmos

type SensAtmos struct {
	Tempambient float32 //  Ambient temperature [degrees Celsius]
	Humidity    float32 //  Relative humidity [%]
}

Atmospheric sensors (temperature, humidity, ...)

func (*SensAtmos) MsgID

func (self *SensAtmos) MsgID() uint8

func (*SensAtmos) MsgName

func (self *SensAtmos) MsgName() string

func (*SensAtmos) Pack

func (self *SensAtmos) Pack(p *Packet) error

func (*SensAtmos) Unpack

func (self *SensAtmos) Unpack(p *Packet) error

type SensBatmon

type SensBatmon struct {
	Temperature    float32 // Battery pack temperature in [deg C]
	Voltage        uint16  // Battery pack voltage in [mV]
	Current        int16   // Battery pack current in [mA]
	Batterystatus  uint16  // Battery monitor status report bits in Hex
	Serialnumber   uint16  // Battery monitor serial number in Hex
	Hostfetcontrol uint16  // Battery monitor sensor host FET control in Hex
	Cellvoltage1   uint16  // Battery pack cell 1 voltage in [mV]
	Cellvoltage2   uint16  // Battery pack cell 2 voltage in [mV]
	Cellvoltage3   uint16  // Battery pack cell 3 voltage in [mV]
	Cellvoltage4   uint16  // Battery pack cell 4 voltage in [mV]
	Cellvoltage5   uint16  // Battery pack cell 5 voltage in [mV]
	Cellvoltage6   uint16  // Battery pack cell 6 voltage in [mV]
	Soc            uint8   // Battery pack state-of-charge
}

Battery pack monitoring data for Li-Ion batteries

func (*SensBatmon) MsgID

func (self *SensBatmon) MsgID() uint8

func (*SensBatmon) MsgName

func (self *SensBatmon) MsgName() string

func (*SensBatmon) Pack

func (self *SensBatmon) Pack(p *Packet) error

func (*SensBatmon) Unpack

func (self *SensBatmon) Unpack(p *Packet) error

type SensMppt

type SensMppt struct {
	MpptTimestamp uint64  //  MPPT last timestamp
	Mppt1Volt     float32 //  MPPT1 voltage
	Mppt1Amp      float32 //  MPPT1 current
	Mppt2Volt     float32 //  MPPT2 voltage
	Mppt2Amp      float32 //  MPPT2 current
	Mppt3Volt     float32 //  MPPT3 voltage
	Mppt3Amp      float32 //  MPPT3 current
	Mppt1Pwm      uint16  //  MPPT1 pwm
	Mppt2Pwm      uint16  //  MPPT2 pwm
	Mppt3Pwm      uint16  //  MPPT3 pwm
	Mppt1Status   uint8   //  MPPT1 status
	Mppt2Status   uint8   //  MPPT2 status
	Mppt3Status   uint8   //  MPPT3 status
}

Maximum Power Point Tracker (MPPT) sensor data for solar module power performance tracking

func (*SensMppt) MsgID

func (self *SensMppt) MsgID() uint8

func (*SensMppt) MsgName

func (self *SensMppt) MsgName() string

func (*SensMppt) Pack

func (self *SensMppt) Pack(p *Packet) error

func (*SensMppt) Unpack

func (self *SensMppt) Unpack(p *Packet) error

type SensPower

type SensPower struct {
	Adc121VspbVolt float32 //  Power board voltage sensor reading in volts
	Adc121CspbAmp  float32 //  Power board current sensor reading in amps
	Adc121Cs1Amp   float32 //  Board current sensor 1 reading in amps
	Adc121Cs2Amp   float32 //  Board current sensor 2 reading in amps
}

Voltage and current sensor data

func (*SensPower) MsgID

func (self *SensPower) MsgID() uint8

func (*SensPower) MsgName

func (self *SensPower) MsgName() string

func (*SensPower) Pack

func (self *SensPower) Pack(p *Packet) error

func (*SensPower) Unpack

func (self *SensPower) Unpack(p *Packet) error

type SensorOffsets

type SensorOffsets struct {
	MagDeclination float32 // magnetic declination (radians)
	RawPress       int32   // raw pressure from barometer
	RawTemp        int32   // raw temperature from barometer
	GyroCalX       float32 // gyro X calibration
	GyroCalY       float32 // gyro Y calibration
	GyroCalZ       float32 // gyro Z calibration
	AccelCalX      float32 // accel X calibration
	AccelCalY      float32 // accel Y calibration
	AccelCalZ      float32 // accel Z calibration
	MagOfsX        int16   // magnetometer X offset
	MagOfsY        int16   // magnetometer Y offset
	MagOfsZ        int16   // magnetometer Z offset
}

Offsets and calibrations values for hardware

sensors. This makes it easier to debug the calibration process.

func (*SensorOffsets) MsgID

func (self *SensorOffsets) MsgID() uint8

func (*SensorOffsets) MsgName

func (self *SensorOffsets) MsgName() string

func (*SensorOffsets) Pack

func (self *SensorOffsets) Pack(p *Packet) error

func (*SensorOffsets) Unpack

func (self *SensorOffsets) Unpack(p *Packet) error

type SensorpodStatus

type SensorpodStatus struct {
	Timestamp           uint64 // Timestamp in linuxtime [ms] (since 1.1.1970)
	FreeSpace           uint16 // Free space available in recordings directory in [Gb] * 1e2
	VisensorRate1       uint8  // Rate of ROS topic 1
	VisensorRate2       uint8  // Rate of ROS topic 2
	VisensorRate3       uint8  // Rate of ROS topic 3
	VisensorRate4       uint8  // Rate of ROS topic 4
	RecordingNodesCount uint8  // Number of recording nodes
	CpuTemp             uint8  // Temperature of sensorpod CPU in [deg C]
}

Monitoring of sensorpod status

func (*SensorpodStatus) MsgID

func (self *SensorpodStatus) MsgID() uint8

func (*SensorpodStatus) MsgName

func (self *SensorpodStatus) MsgName() string

func (*SensorpodStatus) Pack

func (self *SensorpodStatus) Pack(p *Packet) error

func (*SensorpodStatus) Unpack

func (self *SensorpodStatus) Unpack(p *Packet) error

type SerialControl

type SerialControl struct {
	Baudrate uint32    // Baudrate of transfer. Zero means no change.
	Timeout  uint16    // Timeout for reply data in milliseconds
	Device   uint8     // See SERIAL_CONTROL_DEV enum
	Flags    uint8     // See SERIAL_CONTROL_FLAG enum
	Count    uint8     // how many bytes in this transfer
	Data     [70]uint8 // serial data
}

Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate.

func (*SerialControl) MsgID

func (self *SerialControl) MsgID() uint8

func (*SerialControl) MsgName

func (self *SerialControl) MsgName() string

func (*SerialControl) Pack

func (self *SerialControl) Pack(p *Packet) error

func (*SerialControl) Unpack

func (self *SerialControl) Unpack(p *Packet) error

type SerialUdbExtraF13

type SerialUdbExtraF13 struct {
	SueLatOrigin int32 // Serial UDB Extra MP Origin Latitude
	SueLonOrigin int32 // Serial UDB Extra MP Origin Longitude
	SueAltOrigin int32 // Serial UDB Extra MP Origin Altitude Above Sea Level
	SueWeekNo    int16 // Serial UDB Extra GPS Week Number
}

Backwards compatible version of SERIAL_UDB_EXTRA F13: format

func (*SerialUdbExtraF13) MsgID

func (self *SerialUdbExtraF13) MsgID() uint8

func (*SerialUdbExtraF13) MsgName

func (self *SerialUdbExtraF13) MsgName() string

func (*SerialUdbExtraF13) Pack

func (self *SerialUdbExtraF13) Pack(p *Packet) error

func (*SerialUdbExtraF13) Unpack

func (self *SerialUdbExtraF13) Unpack(p *Packet) error

type SerialUdbExtraF14

type SerialUdbExtraF14 struct {
	SueTrapSource     uint32 // Serial UDB Extra Type Program Address of Last Trap
	SueRcon           int16  // Serial UDB Extra Reboot Regitster of DSPIC
	SueTrapFlags      int16  // Serial UDB Extra  Last dspic Trap Flags
	SueOscFailCount   int16  // Serial UDB Extra Number of Ocillator Failures
	SueWindEstimation uint8  // Serial UDB Extra Wind Estimation Enabled
	SueGpsType        uint8  // Serial UDB Extra Type of GPS Unit
	SueDr             uint8  // Serial UDB Extra Dead Reckoning Enabled
	SueBoardType      uint8  // Serial UDB Extra Type of UDB Hardware
	SueAirframe       uint8  // Serial UDB Extra Type of Airframe
	SueClockConfig    uint8  // Serial UDB Extra UDB Internal Clock Configuration
	SueFlightPlanType uint8  // Serial UDB Extra Type of Flight Plan
}

Backwards compatible version of SERIAL_UDB_EXTRA F14: format

func (*SerialUdbExtraF14) MsgID

func (self *SerialUdbExtraF14) MsgID() uint8

func (*SerialUdbExtraF14) MsgName

func (self *SerialUdbExtraF14) MsgName() string

func (*SerialUdbExtraF14) Pack

func (self *SerialUdbExtraF14) Pack(p *Packet) error

func (*SerialUdbExtraF14) Unpack

func (self *SerialUdbExtraF14) Unpack(p *Packet) error

type SerialUdbExtraF15

type SerialUdbExtraF15 struct {
	SueIdVehicleModelName    [40]uint8 // Serial UDB Extra Model Name Of Vehicle
	SueIdVehicleRegistration [20]uint8 // Serial UDB Extra Registraton Number of Vehicle
}

Backwards compatible version of SERIAL_UDB_EXTRA F15 and F16: format

func (*SerialUdbExtraF15) MsgID

func (self *SerialUdbExtraF15) MsgID() uint8

func (*SerialUdbExtraF15) MsgName

func (self *SerialUdbExtraF15) MsgName() string

func (*SerialUdbExtraF15) Pack

func (self *SerialUdbExtraF15) Pack(p *Packet) error

func (*SerialUdbExtraF15) Unpack

func (self *SerialUdbExtraF15) Unpack(p *Packet) error

type SerialUdbExtraF16

type SerialUdbExtraF16 struct {
	SueIdLeadPilot    [40]uint8 // Serial UDB Extra Name of Expected Lead Pilot
	SueIdDiyDronesUrl [70]uint8 // Serial UDB Extra URL of Lead Pilot or Team
}

func (*SerialUdbExtraF16) MsgID

func (self *SerialUdbExtraF16) MsgID() uint8

func (*SerialUdbExtraF16) MsgName

func (self *SerialUdbExtraF16) MsgName() string

func (*SerialUdbExtraF16) Pack

func (self *SerialUdbExtraF16) Pack(p *Packet) error

func (*SerialUdbExtraF16) Unpack

func (self *SerialUdbExtraF16) Unpack(p *Packet) error

type SerialUdbExtraF2A

type SerialUdbExtraF2A struct {
	SueTime           uint32 // Serial UDB Extra Time
	SueLatitude       int32  // Serial UDB Extra Latitude
	SueLongitude      int32  // Serial UDB Extra Longitude
	SueAltitude       int32  // Serial UDB Extra Altitude
	SueWaypointIndex  uint16 // Serial UDB Extra Waypoint Index
	SueRmat0          int16  // Serial UDB Extra Rmat 0
	SueRmat1          int16  // Serial UDB Extra Rmat 1
	SueRmat2          int16  // Serial UDB Extra Rmat 2
	SueRmat3          int16  // Serial UDB Extra Rmat 3
	SueRmat4          int16  // Serial UDB Extra Rmat 4
	SueRmat5          int16  // Serial UDB Extra Rmat 5
	SueRmat6          int16  // Serial UDB Extra Rmat 6
	SueRmat7          int16  // Serial UDB Extra Rmat 7
	SueRmat8          int16  // Serial UDB Extra Rmat 8
	SueCog            uint16 // Serial UDB Extra GPS Course Over Ground
	SueSog            int16  // Serial UDB Extra Speed Over Ground
	SueCpuLoad        uint16 // Serial UDB Extra CPU Load
	SueVoltageMilis   int16  // Serial UDB Extra Voltage in MilliVolts
	SueAirSpeed3dimu  uint16 // Serial UDB Extra 3D IMU Air Speed
	SueEstimatedWind0 int16  // Serial UDB Extra Estimated Wind 0
	SueEstimatedWind1 int16  // Serial UDB Extra Estimated Wind 1
	SueEstimatedWind2 int16  // Serial UDB Extra Estimated Wind 2
	SueMagfieldearth0 int16  // Serial UDB Extra Magnetic Field Earth 0
	SueMagfieldearth1 int16  // Serial UDB Extra Magnetic Field Earth 1
	SueMagfieldearth2 int16  // Serial UDB Extra Magnetic Field Earth 2
	SueSvs            int16  // Serial UDB Extra Number of Sattelites in View
	SueHdop           int16  // Serial UDB Extra GPS Horizontal Dilution of Precision
	SueStatus         uint8  // Serial UDB Extra Status
}

Backwards compatible MAVLink version of SERIAL_UDB_EXTRA - F2: Format Part A

func (*SerialUdbExtraF2A) MsgID

func (self *SerialUdbExtraF2A) MsgID() uint8

func (*SerialUdbExtraF2A) MsgName

func (self *SerialUdbExtraF2A) MsgName() string

func (*SerialUdbExtraF2A) Pack

func (self *SerialUdbExtraF2A) Pack(p *Packet) error

func (*SerialUdbExtraF2A) Unpack

func (self *SerialUdbExtraF2A) Unpack(p *Packet) error

type SerialUdbExtraF2B

type SerialUdbExtraF2B struct {
	SueTime            uint32 // Serial UDB Extra Time
	SueFlags           uint32 // Serial UDB Extra Status Flags
	SuePwmInput1       int16  // Serial UDB Extra PWM Input Channel 1
	SuePwmInput2       int16  // Serial UDB Extra PWM Input Channel 2
	SuePwmInput3       int16  // Serial UDB Extra PWM Input Channel 3
	SuePwmInput4       int16  // Serial UDB Extra PWM Input Channel 4
	SuePwmInput5       int16  // Serial UDB Extra PWM Input Channel 5
	SuePwmInput6       int16  // Serial UDB Extra PWM Input Channel 6
	SuePwmInput7       int16  // Serial UDB Extra PWM Input Channel 7
	SuePwmInput8       int16  // Serial UDB Extra PWM Input Channel 8
	SuePwmInput9       int16  // Serial UDB Extra PWM Input Channel 9
	SuePwmInput10      int16  // Serial UDB Extra PWM Input Channel 10
	SuePwmOutput1      int16  // Serial UDB Extra PWM Output Channel 1
	SuePwmOutput2      int16  // Serial UDB Extra PWM Output Channel 2
	SuePwmOutput3      int16  // Serial UDB Extra PWM Output Channel 3
	SuePwmOutput4      int16  // Serial UDB Extra PWM Output Channel 4
	SuePwmOutput5      int16  // Serial UDB Extra PWM Output Channel 5
	SuePwmOutput6      int16  // Serial UDB Extra PWM Output Channel 6
	SuePwmOutput7      int16  // Serial UDB Extra PWM Output Channel 7
	SuePwmOutput8      int16  // Serial UDB Extra PWM Output Channel 8
	SuePwmOutput9      int16  // Serial UDB Extra PWM Output Channel 9
	SuePwmOutput10     int16  // Serial UDB Extra PWM Output Channel 10
	SueImuLocationX    int16  // Serial UDB Extra IMU Location X
	SueImuLocationY    int16  // Serial UDB Extra IMU Location Y
	SueImuLocationZ    int16  // Serial UDB Extra IMU Location Z
	SueOscFails        int16  // Serial UDB Extra Oscillator Failure Count
	SueImuVelocityX    int16  // Serial UDB Extra IMU Velocity X
	SueImuVelocityY    int16  // Serial UDB Extra IMU Velocity Y
	SueImuVelocityZ    int16  // Serial UDB Extra IMU Velocity Z
	SueWaypointGoalX   int16  // Serial UDB Extra Current Waypoint Goal X
	SueWaypointGoalY   int16  // Serial UDB Extra Current Waypoint Goal Y
	SueWaypointGoalZ   int16  // Serial UDB Extra Current Waypoint Goal Z
	SueMemoryStackFree int16  // Serial UDB Extra Stack Memory Free
}

Backwards compatible version of SERIAL_UDB_EXTRA - F2: Part B

func (*SerialUdbExtraF2B) MsgID

func (self *SerialUdbExtraF2B) MsgID() uint8

func (*SerialUdbExtraF2B) MsgName

func (self *SerialUdbExtraF2B) MsgName() string

func (*SerialUdbExtraF2B) Pack

func (self *SerialUdbExtraF2B) Pack(p *Packet) error

func (*SerialUdbExtraF2B) Unpack

func (self *SerialUdbExtraF2B) Unpack(p *Packet) error

type SerialUdbExtraF4

type SerialUdbExtraF4 struct {
	SueRollStabilizationAilerons uint8 // Serial UDB Extra Roll Stabilization with Ailerons Enabled
	SueRollStabilizationRudder   uint8 // Serial UDB Extra Roll Stabilization with Rudder Enabled
	SuePitchStabilization        uint8 // Serial UDB Extra Pitch Stabilization Enabled
	SueYawStabilizationRudder    uint8 // Serial UDB Extra Yaw Stabilization using Rudder Enabled
	SueYawStabilizationAileron   uint8 // Serial UDB Extra Yaw Stabilization using Ailerons Enabled
	SueAileronNavigation         uint8 // Serial UDB Extra Navigation with Ailerons Enabled
	SueRudderNavigation          uint8 // Serial UDB Extra Navigation with Rudder Enabled
	SueAltitudeholdStabilized    uint8 // Serial UDB Extra Type of Alitude Hold when in Stabilized Mode
	SueAltitudeholdWaypoint      uint8 // Serial UDB Extra Type of Alitude Hold when in Waypoint Mode
	SueRacingMode                uint8 // Serial UDB Extra Firmware racing mode enabled
}

Backwards compatible version of SERIAL_UDB_EXTRA F4: format

func (*SerialUdbExtraF4) MsgID

func (self *SerialUdbExtraF4) MsgID() uint8

func (*SerialUdbExtraF4) MsgName

func (self *SerialUdbExtraF4) MsgName() string

func (*SerialUdbExtraF4) Pack

func (self *SerialUdbExtraF4) Pack(p *Packet) error

func (*SerialUdbExtraF4) Unpack

func (self *SerialUdbExtraF4) Unpack(p *Packet) error

type SerialUdbExtraF5

type SerialUdbExtraF5 struct {
	SueYawkpAileron            float32 // Serial UDB YAWKP_AILERON Gain for Proporional control of navigation
	SueYawkdAileron            float32 // Serial UDB YAWKD_AILERON Gain for Rate control of navigation
	SueRollkp                  float32 // Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization
	SueRollkd                  float32 // Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization
	SueYawStabilizationAileron float32 // YAW_STABILIZATION_AILERON Proportional control
	SueAileronBoost            float32 // Gain For Boosting Manual Aileron control When Plane Stabilized
}

Backwards compatible version of SERIAL_UDB_EXTRA F5: format

func (*SerialUdbExtraF5) MsgID

func (self *SerialUdbExtraF5) MsgID() uint8

func (*SerialUdbExtraF5) MsgName

func (self *SerialUdbExtraF5) MsgName() string

func (*SerialUdbExtraF5) Pack

func (self *SerialUdbExtraF5) Pack(p *Packet) error

func (*SerialUdbExtraF5) Unpack

func (self *SerialUdbExtraF5) Unpack(p *Packet) error

type SerialUdbExtraF6

type SerialUdbExtraF6 struct {
	SuePitchgain     float32 // Serial UDB Extra PITCHGAIN Proportional Control
	SuePitchkd       float32 // Serial UDB Extra Pitch Rate Control
	SueRudderElevMix float32 // Serial UDB Extra Rudder to Elevator Mix
	SueRollElevMix   float32 // Serial UDB Extra Roll to Elevator Mix
	SueElevatorBoost float32 // Gain For Boosting Manual Elevator control When Plane Stabilized
}

Backwards compatible version of SERIAL_UDB_EXTRA F6: format

func (*SerialUdbExtraF6) MsgID

func (self *SerialUdbExtraF6) MsgID() uint8

func (*SerialUdbExtraF6) MsgName

func (self *SerialUdbExtraF6) MsgName() string

func (*SerialUdbExtraF6) Pack

func (self *SerialUdbExtraF6) Pack(p *Packet) error

func (*SerialUdbExtraF6) Unpack

func (self *SerialUdbExtraF6) Unpack(p *Packet) error

type SerialUdbExtraF7

type SerialUdbExtraF7 struct {
	SueYawkpRudder  float32 // Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation
	SueYawkdRudder  float32 // Serial UDB YAWKD_RUDDER Gain for Rate control of navigation
	SueRollkpRudder float32 // Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization
	SueRollkdRudder float32 // Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization
	SueRudderBoost  float32 // SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized
	SueRtlPitchDown float32 // Serial UDB Extra Return To Landing - Angle to Pitch Plane Down
}

Backwards compatible version of SERIAL_UDB_EXTRA F7: format

func (*SerialUdbExtraF7) MsgID

func (self *SerialUdbExtraF7) MsgID() uint8

func (*SerialUdbExtraF7) MsgName

func (self *SerialUdbExtraF7) MsgName() string

func (*SerialUdbExtraF7) Pack

func (self *SerialUdbExtraF7) Pack(p *Packet) error

func (*SerialUdbExtraF7) Unpack

func (self *SerialUdbExtraF7) Unpack(p *Packet) error

type SerialUdbExtraF8

type SerialUdbExtraF8 struct {
	SueHeightTargetMax    float32 // Serial UDB Extra HEIGHT_TARGET_MAX
	SueHeightTargetMin    float32 // Serial UDB Extra HEIGHT_TARGET_MIN
	SueAltHoldThrottleMin float32 // Serial UDB Extra ALT_HOLD_THROTTLE_MIN
	SueAltHoldThrottleMax float32 // Serial UDB Extra ALT_HOLD_THROTTLE_MAX
	SueAltHoldPitchMin    float32 // Serial UDB Extra ALT_HOLD_PITCH_MIN
	SueAltHoldPitchMax    float32 // Serial UDB Extra ALT_HOLD_PITCH_MAX
	SueAltHoldPitchHigh   float32 // Serial UDB Extra ALT_HOLD_PITCH_HIGH
}

Backwards compatible version of SERIAL_UDB_EXTRA F8: format

func (*SerialUdbExtraF8) MsgID

func (self *SerialUdbExtraF8) MsgID() uint8

func (*SerialUdbExtraF8) MsgName

func (self *SerialUdbExtraF8) MsgName() string

func (*SerialUdbExtraF8) Pack

func (self *SerialUdbExtraF8) Pack(p *Packet) error

func (*SerialUdbExtraF8) Unpack

func (self *SerialUdbExtraF8) Unpack(p *Packet) error

type ServoOutputRaw

type ServoOutputRaw struct {
	TimeUsec  uint32 // Timestamp (microseconds since system boot)
	Servo1Raw uint16 // Servo output 1 value, in microseconds
	Servo2Raw uint16 // Servo output 2 value, in microseconds
	Servo3Raw uint16 // Servo output 3 value, in microseconds
	Servo4Raw uint16 // Servo output 4 value, in microseconds
	Servo5Raw uint16 // Servo output 5 value, in microseconds
	Servo6Raw uint16 // Servo output 6 value, in microseconds
	Servo7Raw uint16 // Servo output 7 value, in microseconds
	Servo8Raw uint16 // Servo output 8 value, in microseconds
	Port      uint8  // Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
}

The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%.

func (*ServoOutputRaw) MsgID

func (self *ServoOutputRaw) MsgID() uint8

func (*ServoOutputRaw) MsgName

func (self *ServoOutputRaw) MsgName() string

func (*ServoOutputRaw) Pack

func (self *ServoOutputRaw) Pack(p *Packet) error

func (*ServoOutputRaw) Unpack

func (self *ServoOutputRaw) Unpack(p *Packet) error

type SetActuatorControlTarget

type SetActuatorControlTarget struct {
	TimeUsec        uint64     // Timestamp (micros since boot or Unix epoch)
	Controls        [8]float32 // Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.
	GroupMlx        uint8      // Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.
	TargetSystem    uint8      // System ID
	TargetComponent uint8      // Component ID
}

Set the vehicle attitude and body angular rates.

func (*SetActuatorControlTarget) MsgID

func (self *SetActuatorControlTarget) MsgID() uint8

func (*SetActuatorControlTarget) MsgName

func (self *SetActuatorControlTarget) MsgName() string

func (*SetActuatorControlTarget) Pack

func (self *SetActuatorControlTarget) Pack(p *Packet) error

func (*SetActuatorControlTarget) Unpack

func (self *SetActuatorControlTarget) Unpack(p *Packet) error

type SetAttitudeTarget

type SetAttitudeTarget struct {
	TimeBootMs      uint32     // Timestamp in milliseconds since system boot
	Q               [4]float32 // Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
	BodyRollRate    float32    // Body roll rate in radians per second
	BodyPitchRate   float32    // Body roll rate in radians per second
	BodyYawRate     float32    // Body roll rate in radians per second
	Thrust          float32    // Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
	TargetSystem    uint8      // System ID
	TargetComponent uint8      // Component ID
	TypeMask        uint8      // Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude
}

Set the vehicle attitude and body angular rates.

func (*SetAttitudeTarget) MsgID

func (self *SetAttitudeTarget) MsgID() uint8

func (*SetAttitudeTarget) MsgName

func (self *SetAttitudeTarget) MsgName() string

func (*SetAttitudeTarget) Pack

func (self *SetAttitudeTarget) Pack(p *Packet) error

func (*SetAttitudeTarget) Unpack

func (self *SetAttitudeTarget) Unpack(p *Packet) error

type SetCamShutter

type SetCamShutter struct {
	Gain       float32 // Camera gain
	Interval   uint16  // Shutter interval, in microseconds
	Exposure   uint16  // Exposure time, in microseconds
	CamNo      uint8   // Camera id
	CamMode    uint8   // Camera mode: 0 = auto, 1 = manual
	TriggerPin uint8   // Trigger pin, 0-3 for PtGrey FireFly
}

func (*SetCamShutter) MsgID

func (self *SetCamShutter) MsgID() uint8

func (*SetCamShutter) MsgName

func (self *SetCamShutter) MsgName() string

func (*SetCamShutter) Pack

func (self *SetCamShutter) Pack(p *Packet) error

func (*SetCamShutter) Unpack

func (self *SetCamShutter) Unpack(p *Packet) error

type SetGpsGlobalOrigin

type SetGpsGlobalOrigin struct {
	Latitude     int32 // Latitude (WGS84), in degrees * 1E7
	Longitude    int32 // Longitude (WGS84, in degrees * 1E7
	Altitude     int32 // Altitude (AMSL), in meters * 1000 (positive for up)
	TargetSystem uint8 // System ID
}

As local waypoints exist, the global MISSION reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor.

func (*SetGpsGlobalOrigin) MsgID

func (self *SetGpsGlobalOrigin) MsgID() uint8

func (*SetGpsGlobalOrigin) MsgName

func (self *SetGpsGlobalOrigin) MsgName() string

func (*SetGpsGlobalOrigin) Pack

func (self *SetGpsGlobalOrigin) Pack(p *Packet) error

func (*SetGpsGlobalOrigin) Unpack

func (self *SetGpsGlobalOrigin) Unpack(p *Packet) error

type SetHomePosition

type SetHomePosition struct {
	Latitude     int32      // Latitude (WGS84), in degrees * 1E7
	Longitude    int32      // Longitude (WGS84, in degrees * 1E7
	Altitude     int32      // Altitude (AMSL), in meters * 1000 (positive for up)
	X            float32    // Local X position of this position in the local coordinate frame
	Y            float32    // Local Y position of this position in the local coordinate frame
	Z            float32    // Local Z position of this position in the local coordinate frame
	Q            [4]float32 // World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
	ApproachX    float32    // 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.
	ApproachY    float32    // 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.
	ApproachZ    float32    // 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.
	TargetSystem uint8      // System ID.
}

The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector.

func (*SetHomePosition) MsgID

func (self *SetHomePosition) MsgID() uint8

func (*SetHomePosition) MsgName

func (self *SetHomePosition) MsgName() string

func (*SetHomePosition) Pack

func (self *SetHomePosition) Pack(p *Packet) error

func (*SetHomePosition) Unpack

func (self *SetHomePosition) Unpack(p *Packet) error

type SetMagOffsets

type SetMagOffsets struct {
	MagOfsX         int16 // magnetometer X offset
	MagOfsY         int16 // magnetometer Y offset
	MagOfsZ         int16 // magnetometer Z offset
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Deprecated. Use MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS instead. Set the magnetometer offsets

func (*SetMagOffsets) MsgID

func (self *SetMagOffsets) MsgID() uint8

func (*SetMagOffsets) MsgName

func (self *SetMagOffsets) MsgName() string

func (*SetMagOffsets) Pack

func (self *SetMagOffsets) Pack(p *Packet) error

func (*SetMagOffsets) Unpack

func (self *SetMagOffsets) Unpack(p *Packet) error

type SetMode

type SetMode struct {
	CustomMode   uint32 // The new autopilot-specific mode. This field can be ignored by an autopilot.
	TargetSystem uint8  // The system setting the mode
	BaseMode     uint8  // The new base mode
}

Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.

func (*SetMode) MsgID

func (self *SetMode) MsgID() uint8

func (*SetMode) MsgName

func (self *SetMode) MsgName() string

func (*SetMode) Pack

func (self *SetMode) Pack(p *Packet) error

func (*SetMode) Unpack

func (self *SetMode) Unpack(p *Packet) error

type SetPositionControlOffset

type SetPositionControlOffset struct {
	X               float32 // x position offset
	Y               float32 // y position offset
	Z               float32 // z position offset
	Yaw             float32 // yaw orientation offset in radians, 0 = NORTH
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
}

Message sent to the MAV to set a new offset from the currently controlled position

func (*SetPositionControlOffset) MsgID

func (self *SetPositionControlOffset) MsgID() uint8

func (*SetPositionControlOffset) MsgName

func (self *SetPositionControlOffset) MsgName() string

func (*SetPositionControlOffset) Pack

func (self *SetPositionControlOffset) Pack(p *Packet) error

func (*SetPositionControlOffset) Unpack

func (self *SetPositionControlOffset) Unpack(p *Packet) error

type SetPositionTargetGlobalInt

type SetPositionTargetGlobalInt struct {
	TimeBootMs      uint32  // 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.
	LatInt          int32   // X Position in WGS84 frame in 1e7 * meters
	LonInt          int32   // Y Position in WGS84 frame in 1e7 * meters
	Alt             float32 // Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
	Vx              float32 // X velocity in NED frame in meter / s
	Vy              float32 // Y velocity in NED frame in meter / s
	Vz              float32 // Z velocity in NED frame in meter / s
	Afx             float32 // X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afy             float32 // Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afz             float32 // Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Yaw             float32 // yaw setpoint in rad
	YawRate         float32 // yaw rate setpoint in rad/s
	TypeMask        uint16  // 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. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. 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: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
	CoordinateFrame uint8   // Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
}

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

func (*SetPositionTargetGlobalInt) MsgID

func (self *SetPositionTargetGlobalInt) MsgID() uint8

func (*SetPositionTargetGlobalInt) MsgName

func (self *SetPositionTargetGlobalInt) MsgName() string

func (*SetPositionTargetGlobalInt) Pack

func (self *SetPositionTargetGlobalInt) Pack(p *Packet) error

func (*SetPositionTargetGlobalInt) Unpack

func (self *SetPositionTargetGlobalInt) Unpack(p *Packet) error

type SetPositionTargetLocalNed

type SetPositionTargetLocalNed struct {
	TimeBootMs      uint32  // Timestamp in milliseconds since system boot
	X               float32 // X Position in NED frame in meters
	Y               float32 // Y Position in NED frame in meters
	Z               float32 // Z Position in NED frame in meters (note, altitude is negative in NED)
	Vx              float32 // X velocity in NED frame in meter / s
	Vy              float32 // Y velocity in NED frame in meter / s
	Vz              float32 // Z velocity in NED frame in meter / s
	Afx             float32 // X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afy             float32 // Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afz             float32 // Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Yaw             float32 // yaw setpoint in rad
	YawRate         float32 // yaw rate setpoint in rad/s
	TypeMask        uint16  // 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. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. 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: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
	CoordinateFrame uint8   // Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
}

Set vehicle position, velocity and acceleration setpoint in local frame.

func (*SetPositionTargetLocalNed) MsgID

func (self *SetPositionTargetLocalNed) MsgID() uint8

func (*SetPositionTargetLocalNed) MsgName

func (self *SetPositionTargetLocalNed) MsgName() string

func (*SetPositionTargetLocalNed) Pack

func (self *SetPositionTargetLocalNed) Pack(p *Packet) error

func (*SetPositionTargetLocalNed) Unpack

func (self *SetPositionTargetLocalNed) Unpack(p *Packet) error

type SimState

type SimState struct {
	Q1         float32 // True attitude quaternion component 1, w (1 in null-rotation)
	Q2         float32 // True attitude quaternion component 2, x (0 in null-rotation)
	Q3         float32 // True attitude quaternion component 3, y (0 in null-rotation)
	Q4         float32 // True attitude quaternion component 4, z (0 in null-rotation)
	Roll       float32 // Attitude roll expressed as Euler angles, not recommended except for human-readable outputs
	Pitch      float32 // Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs
	Yaw        float32 // Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs
	Xacc       float32 // X acceleration m/s/s
	Yacc       float32 // Y acceleration m/s/s
	Zacc       float32 // Z acceleration m/s/s
	Xgyro      float32 // Angular speed around X axis rad/s
	Ygyro      float32 // Angular speed around Y axis rad/s
	Zgyro      float32 // Angular speed around Z axis rad/s
	Lat        float32 // Latitude in degrees
	Lon        float32 // Longitude in degrees
	Alt        float32 // Altitude in meters
	StdDevHorz float32 // Horizontal position standard deviation
	StdDevVert float32 // Vertical position standard deviation
	Vn         float32 // True velocity in m/s in NORTH direction in earth-fixed NED frame
	Ve         float32 // True velocity in m/s in EAST direction in earth-fixed NED frame
	Vd         float32 // True velocity in m/s in DOWN direction in earth-fixed NED frame
}

Status of simulation environment, if used

func (*SimState) MsgID

func (self *SimState) MsgID() uint8

func (*SimState) MsgName

func (self *SimState) MsgName() string

func (*SimState) Pack

func (self *SimState) Pack(p *Packet) error

func (*SimState) Unpack

func (self *SimState) Unpack(p *Packet) error

type Simstate

type Simstate struct {
	Roll  float32 // Roll angle (rad)
	Pitch float32 // Pitch angle (rad)
	Yaw   float32 // Yaw angle (rad)
	Xacc  float32 // X acceleration m/s/s
	Yacc  float32 // Y acceleration m/s/s
	Zacc  float32 // Z acceleration m/s/s
	Xgyro float32 // Angular speed around X axis rad/s
	Ygyro float32 // Angular speed around Y axis rad/s
	Zgyro float32 // Angular speed around Z axis rad/s
	Lat   int32   // Latitude in degrees * 1E7
	Lng   int32   // Longitude in degrees * 1E7
}

Status of simulation environment, if used

func (*Simstate) MsgID

func (self *Simstate) MsgID() uint8

func (*Simstate) MsgName

func (self *Simstate) MsgName() string

func (*Simstate) Pack

func (self *Simstate) Pack(p *Packet) error

func (*Simstate) Unpack

func (self *Simstate) Unpack(p *Packet) error

type Statustext

type Statustext struct {
	Severity uint8    // Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
	Text     [50]byte // Status text message, without null termination character
}

Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz).

func (*Statustext) MsgID

func (self *Statustext) MsgID() uint8

func (*Statustext) MsgName

func (self *Statustext) MsgName() string

func (*Statustext) Pack

func (self *Statustext) Pack(p *Packet) error

func (*Statustext) Unpack

func (self *Statustext) Unpack(p *Packet) error

type SysStatus

type SysStatus struct {
	OnboardControlSensorsPresent uint32 // Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
	OnboardControlSensorsEnabled uint32 // Bitmask showing which onboard controllers and sensors are enabled:  Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
	OnboardControlSensorsHealth  uint32 // Bitmask showing which onboard controllers and sensors are operational or have an error:  Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
	Load                         uint16 // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
	VoltageBattery               uint16 // Battery voltage, in millivolts (1 = 1 millivolt)
	CurrentBattery               int16  // Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
	DropRateComm                 uint16 // Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
	ErrorsComm                   uint16 // Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
	ErrorsCount1                 uint16 // Autopilot-specific errors
	ErrorsCount2                 uint16 // Autopilot-specific errors
	ErrorsCount3                 uint16 // Autopilot-specific errors
	ErrorsCount4                 uint16 // Autopilot-specific errors
	BatteryRemaining             int8   // Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
}

The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.

func (*SysStatus) MsgID

func (self *SysStatus) MsgID() uint8

func (*SysStatus) MsgName

func (self *SysStatus) MsgName() string

func (*SysStatus) Pack

func (self *SysStatus) Pack(p *Packet) error

func (*SysStatus) Unpack

func (self *SysStatus) Unpack(p *Packet) error

type SystemTime

type SystemTime struct {
	TimeUnixUsec uint64 // Timestamp of the master clock in microseconds since UNIX epoch.
	TimeBootMs   uint32 // Timestamp of the component clock since boot time in milliseconds.
}

The system time is the time of the master clock, typically the computer clock of the main onboard computer.

func (*SystemTime) MsgID

func (self *SystemTime) MsgID() uint8

func (*SystemTime) MsgName

func (self *SystemTime) MsgName() string

func (*SystemTime) Pack

func (self *SystemTime) Pack(p *Packet) error

func (*SystemTime) Unpack

func (self *SystemTime) Unpack(p *Packet) error

type TerrainCheck

type TerrainCheck struct {
	Lat int32 // Latitude (degrees *10^7)
	Lon int32 // Longitude (degrees *10^7)
}

Request that the vehicle report terrain height at the given location. Used by GCS to check if vehicle has all terrain data needed for a mission.

func (*TerrainCheck) MsgID

func (self *TerrainCheck) MsgID() uint8

func (*TerrainCheck) MsgName

func (self *TerrainCheck) MsgName() string

func (*TerrainCheck) Pack

func (self *TerrainCheck) Pack(p *Packet) error

func (*TerrainCheck) Unpack

func (self *TerrainCheck) Unpack(p *Packet) error

type TerrainData

type TerrainData struct {
	Lat         int32     // Latitude of SW corner of first grid (degrees *10^7)
	Lon         int32     // Longitude of SW corner of first grid (in degrees *10^7)
	GridSpacing uint16    // Grid spacing in meters
	Data        [16]int16 // Terrain data in meters AMSL
	Gridbit     uint8     // bit within the terrain request mask
}

Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST

func (*TerrainData) MsgID

func (self *TerrainData) MsgID() uint8

func (*TerrainData) MsgName

func (self *TerrainData) MsgName() string

func (*TerrainData) Pack

func (self *TerrainData) Pack(p *Packet) error

func (*TerrainData) Unpack

func (self *TerrainData) Unpack(p *Packet) error

type TerrainReport

type TerrainReport struct {
	Lat           int32   // Latitude (degrees *10^7)
	Lon           int32   // Longitude (degrees *10^7)
	TerrainHeight float32 // Terrain height in meters AMSL
	CurrentHeight float32 // Current vehicle height above lat/lon terrain height (meters)
	Spacing       uint16  // grid spacing (zero if terrain at this location unavailable)
	Pending       uint16  // Number of 4x4 terrain blocks waiting to be received or read from disk
	Loaded        uint16  // Number of 4x4 terrain blocks in memory
}

Response from a TERRAIN_CHECK request

func (*TerrainReport) MsgID

func (self *TerrainReport) MsgID() uint8

func (*TerrainReport) MsgName

func (self *TerrainReport) MsgName() string

func (*TerrainReport) Pack

func (self *TerrainReport) Pack(p *Packet) error

func (*TerrainReport) Unpack

func (self *TerrainReport) Unpack(p *Packet) error

type TerrainRequest

type TerrainRequest struct {
	Mask        uint64 // Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)
	Lat         int32  // Latitude of SW corner of first grid (degrees *10^7)
	Lon         int32  // Longitude of SW corner of first grid (in degrees *10^7)
	GridSpacing uint16 // Grid spacing in meters
}

Request for terrain data and terrain status

func (*TerrainRequest) MsgID

func (self *TerrainRequest) MsgID() uint8

func (*TerrainRequest) MsgName

func (self *TerrainRequest) MsgName() string

func (*TerrainRequest) Pack

func (self *TerrainRequest) Pack(p *Packet) error

func (*TerrainRequest) Unpack

func (self *TerrainRequest) Unpack(p *Packet) error

type Timesync

type Timesync struct {
	Tc1 int64 // Time sync timestamp 1
	Ts1 int64 // Time sync timestamp 2
}

Time synchronization message.

func (*Timesync) MsgID

func (self *Timesync) MsgID() uint8

func (*Timesync) MsgName

func (self *Timesync) MsgName() string

func (*Timesync) Pack

func (self *Timesync) Pack(p *Packet) error

func (*Timesync) Unpack

func (self *Timesync) Unpack(p *Packet) error

type UalbertaSysStatus

type UalbertaSysStatus struct {
	Mode    uint8 // System mode, see UALBERTA_AUTOPILOT_MODE ENUM
	NavMode uint8 // Navigation mode, see UALBERTA_NAV_MODE ENUM
	Pilot   uint8 // Pilot mode, see UALBERTA_PILOT_MODE
}

System status specific to ualberta uav

func (*UalbertaSysStatus) MsgID

func (self *UalbertaSysStatus) MsgID() uint8

func (*UalbertaSysStatus) MsgName

func (self *UalbertaSysStatus) MsgName() string

func (*UalbertaSysStatus) Pack

func (self *UalbertaSysStatus) Pack(p *Packet) error

func (*UalbertaSysStatus) Unpack

func (self *UalbertaSysStatus) Unpack(p *Packet) error

type V2Extension

type V2Extension struct {
	MessageType     uint16     // A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings).  If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml.  Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.
	TargetNetwork   uint8      // Network ID (0 for broadcast)
	TargetSystem    uint8      // System ID (0 for broadcast)
	TargetComponent uint8      // Component ID (0 for broadcast)
	Payload         [249]uint8 // Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields.  The entire content of this block is opaque unless you understand any the encoding message_type.  The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
}

Message implementing parts of the V2 payload specs in V1 frames for transitional support.

func (*V2Extension) MsgID

func (self *V2Extension) MsgID() uint8

func (*V2Extension) MsgName

func (self *V2Extension) MsgName() string

func (*V2Extension) Pack

func (self *V2Extension) Pack(p *Packet) error

func (*V2Extension) Unpack

func (self *V2Extension) Unpack(p *Packet) error

type VfrHud

type VfrHud struct {
	Airspeed    float32 // Current airspeed in m/s
	Groundspeed float32 // Current ground speed in m/s
	Alt         float32 // Current altitude (MSL), in meters
	Climb       float32 // Current climb rate in meters/second
	Heading     int16   // Current heading in degrees, in compass units (0..360, 0=north)
	Throttle    uint16  // Current throttle setting in integer percent, 0 to 100
}

Metrics typically displayed on a HUD for fixed wing aircraft

func (*VfrHud) MsgID

func (self *VfrHud) MsgID() uint8

func (*VfrHud) MsgName

func (self *VfrHud) MsgName() string

func (*VfrHud) Pack

func (self *VfrHud) Pack(p *Packet) error

func (*VfrHud) Unpack

func (self *VfrHud) Unpack(p *Packet) error

type Vibration

type Vibration struct {
	TimeUsec   uint64  // Timestamp (micros since boot or Unix epoch)
	VibrationX float32 // Vibration levels on X-axis
	VibrationY float32 // Vibration levels on Y-axis
	VibrationZ float32 // Vibration levels on Z-axis
	Clipping0  uint32  // first accelerometer clipping count
	Clipping1  uint32  // second accelerometer clipping count
	Clipping2  uint32  // third accelerometer clipping count
}

Vibration levels and accelerometer clipping

func (*Vibration) MsgID

func (self *Vibration) MsgID() uint8

func (*Vibration) MsgName

func (self *Vibration) MsgName() string

func (*Vibration) Pack

func (self *Vibration) Pack(p *Packet) error

func (*Vibration) Unpack

func (self *Vibration) Unpack(p *Packet) error

type ViconPositionEstimate

type ViconPositionEstimate struct {
	Usec  uint64  // Timestamp (microseconds, synced to UNIX time or since system boot)
	X     float32 // Global X position
	Y     float32 // Global Y position
	Z     float32 // Global Z position
	Roll  float32 // Roll angle in rad
	Pitch float32 // Pitch angle in rad
	Yaw   float32 // Yaw angle in rad
}

func (*ViconPositionEstimate) MsgID

func (self *ViconPositionEstimate) MsgID() uint8

func (*ViconPositionEstimate) MsgName

func (self *ViconPositionEstimate) MsgName() string

func (*ViconPositionEstimate) Pack

func (self *ViconPositionEstimate) Pack(p *Packet) error

func (*ViconPositionEstimate) Unpack

func (self *ViconPositionEstimate) Unpack(p *Packet) error

type VisionPositionEstimate

type VisionPositionEstimate struct {
	Usec  uint64  // Timestamp (microseconds, synced to UNIX time or since system boot)
	X     float32 // Global X position
	Y     float32 // Global Y position
	Z     float32 // Global Z position
	Roll  float32 // Roll angle in rad
	Pitch float32 // Pitch angle in rad
	Yaw   float32 // Yaw angle in rad
}

func (*VisionPositionEstimate) MsgID

func (self *VisionPositionEstimate) MsgID() uint8

func (*VisionPositionEstimate) MsgName

func (self *VisionPositionEstimate) MsgName() string

func (*VisionPositionEstimate) Pack

func (self *VisionPositionEstimate) Pack(p *Packet) error

func (*VisionPositionEstimate) Unpack

func (self *VisionPositionEstimate) Unpack(p *Packet) error

type VisionSpeedEstimate

type VisionSpeedEstimate struct {
	Usec uint64  // Timestamp (microseconds, synced to UNIX time or since system boot)
	X    float32 // Global X speed
	Y    float32 // Global Y speed
	Z    float32 // Global Z speed
}

func (*VisionSpeedEstimate) MsgID

func (self *VisionSpeedEstimate) MsgID() uint8

func (*VisionSpeedEstimate) MsgName

func (self *VisionSpeedEstimate) MsgName() string

func (*VisionSpeedEstimate) Pack

func (self *VisionSpeedEstimate) Pack(p *Packet) error

func (*VisionSpeedEstimate) Unpack

func (self *VisionSpeedEstimate) Unpack(p *Packet) error

type WatchdogCommand

type WatchdogCommand struct {
	WatchdogId     uint16 // Watchdog ID
	ProcessId      uint16 // Process ID
	TargetSystemId uint8  // Target system ID
	CommandId      uint8  // Command ID
}

func (*WatchdogCommand) MsgID

func (self *WatchdogCommand) MsgID() uint8

func (*WatchdogCommand) MsgName

func (self *WatchdogCommand) MsgName() string

func (*WatchdogCommand) Pack

func (self *WatchdogCommand) Pack(p *Packet) error

func (*WatchdogCommand) Unpack

func (self *WatchdogCommand) Unpack(p *Packet) error

type WatchdogHeartbeat

type WatchdogHeartbeat struct {
	WatchdogId   uint16 // Watchdog ID
	ProcessCount uint16 // Number of processes
}

func (*WatchdogHeartbeat) MsgID

func (self *WatchdogHeartbeat) MsgID() uint8

func (*WatchdogHeartbeat) MsgName

func (self *WatchdogHeartbeat) MsgName() string

func (*WatchdogHeartbeat) Pack

func (self *WatchdogHeartbeat) Pack(p *Packet) error

func (*WatchdogHeartbeat) Unpack

func (self *WatchdogHeartbeat) Unpack(p *Packet) error

type WatchdogProcessInfo

type WatchdogProcessInfo struct {
	Timeout    int32     // Timeout (seconds)
	WatchdogId uint16    // Watchdog ID
	ProcessId  uint16    // Process ID
	Name       [100]byte // Process name
	Arguments  [147]byte // Process arguments
}

func (*WatchdogProcessInfo) MsgID

func (self *WatchdogProcessInfo) MsgID() uint8

func (*WatchdogProcessInfo) MsgName

func (self *WatchdogProcessInfo) MsgName() string

func (*WatchdogProcessInfo) Pack

func (self *WatchdogProcessInfo) Pack(p *Packet) error

func (*WatchdogProcessInfo) Unpack

func (self *WatchdogProcessInfo) Unpack(p *Packet) error

type WatchdogProcessStatus

type WatchdogProcessStatus struct {
	Pid        int32  // PID
	WatchdogId uint16 // Watchdog ID
	ProcessId  uint16 // Process ID
	Crashes    uint16 // Number of crashes
	State      uint8  // Is running / finished / suspended / crashed
	Muted      uint8  // Is muted
}

func (*WatchdogProcessStatus) MsgID

func (self *WatchdogProcessStatus) MsgID() uint8

func (*WatchdogProcessStatus) MsgName

func (self *WatchdogProcessStatus) MsgName() string

func (*WatchdogProcessStatus) Pack

func (self *WatchdogProcessStatus) Pack(p *Packet) error

func (*WatchdogProcessStatus) Unpack

func (self *WatchdogProcessStatus) Unpack(p *Packet) error

type Wind

type Wind struct {
	Direction float32 // wind direction that wind is coming from (degrees)
	Speed     float32 // wind speed in ground plane (m/s)
	SpeedZ    float32 // vertical wind speed (m/s)
}

Wind estimation

func (*Wind) MsgID

func (self *Wind) MsgID() uint8

func (*Wind) MsgName

func (self *Wind) MsgName() string

func (*Wind) Pack

func (self *Wind) Pack(p *Packet) error

func (*Wind) Unpack

func (self *Wind) Unpack(p *Packet) error

Jump to

Keyboard shortcuts

? : This menu
/ : Search site
f or F : Jump to
y or Y : Canonical URL