ardupilotmega

package
v0.13.0 Latest Latest
Warning

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

Go to latest
Published: Jan 29, 2021 License: MIT Imports: 7 Imported by: 0

Documentation

Index

Constants

View Source
const (
	/*AccelcalVehiclePosLevel -  */
	AccelcalVehiclePosLevel = 1
	/*AccelcalVehiclePosLeft -  */
	AccelcalVehiclePosLeft = 2
	/*AccelcalVehiclePosRight -  */
	AccelcalVehiclePosRight = 3
	/*AccelcalVehiclePosNosedown -  */
	AccelcalVehiclePosNosedown = 4
	/*AccelcalVehiclePosNoseup -  */
	AccelcalVehiclePosNoseup = 5
	/*AccelcalVehiclePosBack -  */
	AccelcalVehiclePosBack = 6
	/*AccelcalVehiclePosSuccess -  */
	AccelcalVehiclePosSuccess = 16777215
	/*AccelcalVehiclePosFailed -  */
	AccelcalVehiclePosFailed = 16777216
	/*AccelcalVehiclePosEnumEnd -  */
	AccelcalVehiclePosEnumEnd = 16777217
)

ACCELCAL_VEHICLE_POS -

View Source
const (
	/*MavCmdNAVWaypoint - Navigate to waypoint. */
	MavCmdNAVWaypoint = 16
	/*MavCmdNAVLoiterUnlim - Loiter around this waypoint an unlimited amount of time */
	MavCmdNAVLoiterUnlim = 17
	/*MavCmdNAVLoiterTurns - Loiter around this waypoint for X turns */
	MavCmdNAVLoiterTurns = 18
	/*MavCmdNAVLoiterTime - Loiter around this waypoint for X seconds */
	MavCmdNAVLoiterTime = 19
	/*MavCmdNAVReturnToLaunch - Return to launch location */
	MavCmdNAVReturnToLaunch = 20
	/*MavCmdNAVLand - Land at location. */
	MavCmdNAVLand = 21
	/*MavCmdNAVTakeoff - Takeoff from ground / hand */
	MavCmdNAVTakeoff = 22
	/*MavCmdNAVLandLocal - Land at local position (local frame only) */
	MavCmdNAVLandLocal = 23
	/*MavCmdNAVTakeoffLocal - Takeoff from local position (local frame only) */
	MavCmdNAVTakeoffLocal = 24
	/*MavCmdNAVFollow - Vehicle following, i.e. this waypoint represents the position of a moving vehicle */
	MavCmdNAVFollow = 25
	/*MavCmdNAVContinueAndChangeAlt - 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. */
	MavCmdNAVContinueAndChangeAlt = 30
	/*MavCmdNAVLoiterToAlt - 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. */
	MavCmdNAVLoiterToAlt = 31
	/*MavCmdDoFollow - Begin following a target */
	MavCmdDoFollow = 32
	/*MavCmdDoFollowReposition - Reposition the MAV after a follow target command has been sent */
	MavCmdDoFollowReposition = 33
	/*MavCmdDoOrbit - Start orbiting on the circumference of a circle defined by the parameters. Setting any value NaN results in using defaults. */
	MavCmdDoOrbit = 34
	/*MavCmdNAVRoi - 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. */
	MavCmdNAVRoi = 80
	/*MavCmdNAVPathplanning - Control autonomous path planning on the MAV. */
	MavCmdNAVPathplanning = 81
	/*MavCmdNAVSplineWaypoint - Navigate to waypoint using a spline path. */
	MavCmdNAVSplineWaypoint = 82
	/*MavCmdNAVAltitudeWait - 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. */
	MavCmdNAVAltitudeWait = 83
	/*MavCmdNAVVtolTakeoff - Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. */
	MavCmdNAVVtolTakeoff = 84
	/*MavCmdNAVVtolLand - Land using VTOL mode */
	MavCmdNAVVtolLand = 85
	/*MavCmdNAVGUIDedEnable - hand control over to an external controller */
	MavCmdNAVGUIDedEnable = 92
	/*MavCmdNAVDelay - Delay the next navigation command a number of seconds or until a specified time */
	MavCmdNAVDelay = 93
	/*MavCmdNAVPayloadPlace - Descend and place payload. Vehicle moves to specified location, descends until it detects a hanging payload has reached the ground, and then releases the payload. If ground is not detected before the reaching the maximum descent value (param1), the command will complete without releasing the payload. */
	MavCmdNAVPayloadPlace = 94
	/*MavCmdNAVLast - NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration */
	MavCmdNAVLast = 95
	/*MavCmdConditionDelay - Delay mission state machine. */
	MavCmdConditionDelay = 112
	/*MavCmdConditionChangeAlt - Ascend/descend at rate.  Delay mission state machine until desired altitude reached. */
	MavCmdConditionChangeAlt = 113
	/*MavCmdConditionDistance - Delay mission state machine until within desired distance of next NAV point. */
	MavCmdConditionDistance = 114
	/*MavCmdConditionYaw - Reach a certain target angle. */
	MavCmdConditionYaw = 115
	/*MavCmdConditionLast - NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration */
	MavCmdConditionLast = 159
	/*MavCmdDoSetMode - Set system mode. */
	MavCmdDoSetMode = 176
	/*MavCmdDoJump - Jump to the desired command in the mission list.  Repeat this action only the specified number of times */
	MavCmdDoJump = 177
	/*MavCmdDoChangeSpeed - Change speed and/or throttle set points. */
	MavCmdDoChangeSpeed = 178
	/*MavCmdDoSetHome - Changes the home location either to the current location or a specified location. */
	MavCmdDoSetHome = 179
	/*MavCmdDoSetParameter - Set a system parameter.  Caution!  Use of this command requires knowledge of the numeric enumeration value of the parameter. */
	MavCmdDoSetParameter = 180
	/*MavCmdDoSetRelay - Set a relay to a condition. */
	MavCmdDoSetRelay = 181
	/*MavCmdDoRepeatRelay - Cycle a relay on and off for a desired number of cycles with a desired period. */
	MavCmdDoRepeatRelay = 182
	/*MavCmdDoSetServo - Set a servo to a desired PWM value. */
	MavCmdDoSetServo = 183
	/*MavCmdDoRepeatServo - Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. */
	MavCmdDoRepeatServo = 184
	/*MavCmdDoFlighttermination - Terminate flight immediately */
	MavCmdDoFlighttermination = 185
	/*MavCmdDoChangeAltitude - Change altitude set point. */
	MavCmdDoChangeAltitude = 186
	/*MavCmdDoLandStart - 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 if not needed. If specified then it will be used to help find the closest landing sequence. */
	MavCmdDoLandStart = 189
	/*MavCmdDoRallyLand - Mission command to perform a landing from a rally point. */
	MavCmdDoRallyLand = 190
	/*MavCmdDoGoAround - Mission command to safely abort an autonomous landing. */
	MavCmdDoGoAround = 191
	/*MavCmdDoReposition - Reposition the vehicle to a specific WGS84 global position. */
	MavCmdDoReposition = 192
	/*MavCmdDoPauseContinue - If in a GPS controlled position mode, hold the current position or continue. */
	MavCmdDoPauseContinue = 193
	/*MavCmdDoSetReverse - Set moving direction to forward or reverse. */
	MavCmdDoSetReverse = 194
	/*MavCmdDoSetRoiLocation - Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. */
	MavCmdDoSetRoiLocation = 195
	/*MavCmdDoSetRoiWpnextOffset - Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. */
	MavCmdDoSetRoiWpnextOffset = 196
	/*MavCmdDoSetRoiNone - Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. */
	MavCmdDoSetRoiNone = 197
	/*MavCmdDoSetRoiSysID - Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. */
	MavCmdDoSetRoiSysID = 198
	/*MavCmdDoControlVIDeo - Control onboard camera system. */
	MavCmdDoControlVIDeo = 200
	/*MavCmdDoSetRoi - 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. */
	MavCmdDoSetRoi = 201
	/*MavCmdDoDigicamConfigure - Configure digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ). */
	MavCmdDoDigicamConfigure = 202
	/*MavCmdDoDigicamControl - Control digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ). */
	MavCmdDoDigicamControl = 203
	/*MavCmdDoMountConfigure - Mission command to configure a camera or antenna mount */
	MavCmdDoMountConfigure = 204
	/*MavCmdDoMountControl - Mission command to control a camera or antenna mount */
	MavCmdDoMountControl = 205
	/*MavCmdDoSetCamTriggDist - Mission command to set camera trigger distance for this flight. The camera is triggered each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera. */
	MavCmdDoSetCamTriggDist = 206
	/*MavCmdDoFenceEnable - Mission command to enable the geofence */
	MavCmdDoFenceEnable = 207
	/*MavCmdDoParachute - Mission command to trigger a parachute */
	MavCmdDoParachute = 208
	/*MavCmdDoMotorTest - Mission command to perform motor test. */
	MavCmdDoMotorTest = 209
	/*MavCmdDoInvertedFlight - Change to/from inverted flight. */
	MavCmdDoInvertedFlight = 210
	/*MavCmdDoGripper - Mission command to operate EPM gripper. */
	MavCmdDoGripper = 211
	/*MavCmdDoAutotuneEnable - Enable/disable autotune. */
	MavCmdDoAutotuneEnable = 212
	/*MavCmdNAVSetYawSpeed - Sets a desired vehicle turn angle and speed change. */
	MavCmdNAVSetYawSpeed = 213
	/*MavCmdDoSetCamTriggInterval - Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera. */
	MavCmdDoSetCamTriggInterval = 214
	/*MavCmdDoMountControlQuat - Mission command to control a camera or antenna mount, using a quaternion as reference. */
	MavCmdDoMountControlQuat = 220
	/*MavCmdDoGUIDedMaster - set id of master controller */
	MavCmdDoGUIDedMaster = 221
	/*MavCmdDoGUIDedLimits - Set limits for external control */
	MavCmdDoGUIDedLimits = 222
	/*MavCmdDoEngineControl - Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines */
	MavCmdDoEngineControl = 223
	/*MavCmdDoSetMissionCurrent - 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). */
	MavCmdDoSetMissionCurrent = 224
	/*MavCmdDoLast - NOP - This command is only used to mark the upper limit of the DO commands in the enumeration */
	MavCmdDoLast = 240
	/*MavCmdPreflightCalibration - Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero. */
	MavCmdPreflightCalibration = 241
	/*MavCmdPreflightSetSensorOffsets - Set sensor offsets. This command will be only accepted if in pre-flight mode. */
	MavCmdPreflightSetSensorOffsets = 242
	/*MavCmdPreflightUavcan - Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. */
	MavCmdPreflightUavcan = 243
	/*MavCmdPreflightStorage - Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. */
	MavCmdPreflightStorage = 245
	/*MavCmdPreflightRebootShutdown - Request the reboot or shutdown of system components. */
	MavCmdPreflightRebootShutdown = 246
	/*MavCmdOverrIDeGoto - Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position. */
	MavCmdOverrIDeGoto = 252
	/*MavCmdMissionStart - start running a mission */
	MavCmdMissionStart = 300
	/*MavCmdComponentArmDisarm - Arms / Disarms a component */
	MavCmdComponentArmDisarm = 400
	/*MavCmdIlluminatorOnOff - Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the sytstem: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light). */
	MavCmdIlluminatorOnOff = 405
	/*MavCmdGetHomePosition - Request the home position from the vehicle. */
	MavCmdGetHomePosition = 410
	/*MavCmdStartRxPair - Starts receiver pairing. */
	MavCmdStartRxPair = 500
	/*MavCmdGetMessageInterval - Request the interval between messages for a particular MAVLink message ID. The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message. */
	MavCmdGetMessageInterval = 510
	/*MavCmdSetMessageInterval - Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM. */
	MavCmdSetMessageInterval = 511
	/*MavCmdRequestMessage - Request the target system(s) emit a single instance of a specified message (i.e. a "one-shot" version of MAV_CMD_SET_MESSAGE_INTERVAL). */
	MavCmdRequestMessage = 512
	/*MavCmdRequestProtocolVersion - Request MAVLink protocol version compatibility */
	MavCmdRequestProtocolVersion = 519
	/*MavCmdRequestAutopilotCapabilities - Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message */
	MavCmdRequestAutopilotCapabilities = 520
	/*MavCmdRequestCameraInformation - Request camera information (CAMERA_INFORMATION). */
	MavCmdRequestCameraInformation = 521
	/*MavCmdRequestCameraSettings - Request camera settings (CAMERA_SETTINGS). */
	MavCmdRequestCameraSettings = 522
	/*MavCmdRequestStorageInformation - Request storage information (STORAGE_INFORMATION). Use the command's target_component to target a specific component's storage. */
	MavCmdRequestStorageInformation = 525
	/*MavCmdStorageFormat - Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage. */
	MavCmdStorageFormat = 526
	/*MavCmdRequestCameraCaptureStatus - Request camera capture status (CAMERA_CAPTURE_STATUS) */
	MavCmdRequestCameraCaptureStatus = 527
	/*MavCmdRequestFlightInformation - Request flight information (FLIGHT_INFORMATION) */
	MavCmdRequestFlightInformation = 528
	/*MavCmdResetCameraSettings - Reset all camera settings to Factory Default */
	MavCmdResetCameraSettings = 529
	/*MavCmdSetCameraMode - Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming. */
	MavCmdSetCameraMode = 530
	/*MavCmdSetCameraZoom - Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success). Use NaN for reserved values. */
	MavCmdSetCameraZoom = 531
	/*MavCmdSetCameraFocus - Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success). Use NaN for reserved values. */
	MavCmdSetCameraFocus = 532
	/*MavCmdJumpTag - Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG. */
	MavCmdJumpTag = 600
	/*MavCmdDoJumpTag - Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. */
	MavCmdDoJumpTag = 601
	/*MavCmdImageStartCapture - Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NaN for reserved values. */
	MavCmdImageStartCapture = 2000
	/*MavCmdImageStopCapture - Stop image capture sequence Use NaN for reserved values. */
	MavCmdImageStopCapture = 2001
	/*MavCmdRequestCameraImageCapture - Re-request a CAMERA_IMAGE_CAPTURE message. Use NaN for reserved values. */
	MavCmdRequestCameraImageCapture = 2002
	/*MavCmdDoTriggerControl - Enable or disable on-board camera triggering system. */
	MavCmdDoTriggerControl = 2003
	/*MavCmdVIDeoStartCapture - Starts video capture (recording). Use NaN for reserved values. */
	MavCmdVIDeoStartCapture = 2500
	/*MavCmdVIDeoStopCapture - Stop the current video capture (recording). Use NaN for reserved values. */
	MavCmdVIDeoStopCapture = 2501
	/*MavCmdVIDeoStartStreaming - Start video streaming */
	MavCmdVIDeoStartStreaming = 2502
	/*MavCmdVIDeoStopStreaming - Stop the given video stream */
	MavCmdVIDeoStopStreaming = 2503
	/*MavCmdRequestVIDeoStreamInformation - Request video stream information (VIDEO_STREAM_INFORMATION) */
	MavCmdRequestVIDeoStreamInformation = 2504
	/*MavCmdRequestVIDeoStreamStatus - Request video stream status (VIDEO_STREAM_STATUS) */
	MavCmdRequestVIDeoStreamStatus = 2505
	/*MavCmdLoggingStart - Request to start streaming logging data over MAVLink (see also LOGGING_DATA message) */
	MavCmdLoggingStart = 2510
	/*MavCmdLoggingStop - Request to stop streaming log data over MAVLink */
	MavCmdLoggingStop = 2511
	/*MavCmdAirframeConfiguration -  */
	MavCmdAirframeConfiguration = 2520
	/*MavCmdControlHighLatency - Request to start/stop transmitting over the high latency telemetry */
	MavCmdControlHighLatency = 2600
	/*MavCmdPanoramaCreate - Create a panorama at the current position */
	MavCmdPanoramaCreate = 2800
	/*MavCmdDoVtolTransition - Request VTOL transition */
	MavCmdDoVtolTransition = 3000
	/*MavCmdArmAuthorizationRequest - Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request. If approved the progress of command_ack message should be set with period of time that this authorization is valid in seconds or in case it was denied it should be set with one of the reasons in ARM_AUTH_DENIED_REASON.
	 */
	MavCmdArmAuthorizationRequest = 3001
	/*MavCmdSetGUIDedSubmodeStandard - This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes.
	 */
	MavCmdSetGUIDedSubmodeStandard = 4000
	/*MavCmdSetGUIDedSubmodeCiRCle - This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position.
	 */
	MavCmdSetGUIDedSubmodeCiRCle = 4001
	/*MavCmdConditionGate - Delay mission state machine until gate has been reached. */
	MavCmdConditionGate = 4501
	/*MavCmdNAVFenceReturnPoint - Fence return point. There can only be one fence return point.
	 */
	MavCmdNAVFenceReturnPoint = 5000
	/*MavCmdNAVFencePolygonVertexInclusion - Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required.
	 */
	MavCmdNAVFencePolygonVertexInclusion = 5001
	/*MavCmdNAVFencePolygonVertexExclusion - Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required.
	 */
	MavCmdNAVFencePolygonVertexExclusion = 5002
	/*MavCmdNAVFenceCiRCleInclusion - Circular fence area. The vehicle must stay inside this area.
	 */
	MavCmdNAVFenceCiRCleInclusion = 5003
	/*MavCmdNAVFenceCiRCleExclusion - Circular fence area. The vehicle must stay outside this area.
	 */
	MavCmdNAVFenceCiRCleExclusion = 5004
	/*MavCmdNAVRallyPoint - Rally point. You can have multiple rally points defined.
	 */
	MavCmdNAVRallyPoint = 5100
	/*MavCmdUavcanGetNodeInfo - Commands the vehicle to respond with a sequence of messages UAVCAN_NODE_INFO, one message per every UAVCAN node that is online. Note that some of the response messages can be lost, which the receiver can detect easily by checking whether every received UAVCAN_NODE_STATUS has a matching message UAVCAN_NODE_INFO received earlier; if not, this command should be sent again in order to request re-transmission of the node information messages. */
	MavCmdUavcanGetNodeInfo = 5200
	/*MavCmdPayloadPrepareDeploy - Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. */
	MavCmdPayloadPrepareDeploy = 30001
	/*MavCmdPayloadControlDeploy - Control the payload deployment. */
	MavCmdPayloadControlDeploy = 30002
	/*MavCmdWaypointUser1 - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. */
	MavCmdWaypointUser1 = 31000
	/*MavCmdWaypointUser2 - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. */
	MavCmdWaypointUser2 = 31001
	/*MavCmdWaypointUser3 - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. */
	MavCmdWaypointUser3 = 31002
	/*MavCmdWaypointUser4 - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. */
	MavCmdWaypointUser4 = 31003
	/*MavCmdWaypointUser5 - User defined waypoint item. Ground Station will show the Vehicle as flying through this item. */
	MavCmdWaypointUser5 = 31004
	/*MavCmdSpatialUser1 - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. */
	MavCmdSpatialUser1 = 31005
	/*MavCmdSpatialUser2 - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. */
	MavCmdSpatialUser2 = 31006
	/*MavCmdSpatialUser3 - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. */
	MavCmdSpatialUser3 = 31007
	/*MavCmdSpatialUser4 - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. */
	MavCmdSpatialUser4 = 31008
	/*MavCmdSpatialUser5 - User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. */
	MavCmdSpatialUser5 = 31009
	/*MavCmdUser1 - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. */
	MavCmdUser1 = 31010
	/*MavCmdUser2 - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. */
	MavCmdUser2 = 31011
	/*MavCmdUser3 - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. */
	MavCmdUser3 = 31012
	/*MavCmdUser4 - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. */
	MavCmdUser4 = 31013
	/*MavCmdUser5 - User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. */
	MavCmdUser5 = 31014
	/*MavCmdPowerOffInitiated - A system wide power-off event has been initiated. */
	MavCmdPowerOffInitiated = 42000
	/*MavCmdSoloBtnFlyClick - FLY button has been clicked. */
	MavCmdSoloBtnFlyClick = 42001
	/*MavCmdSoloBtnFlyHold - FLY button has been held for 1.5 seconds. */
	MavCmdSoloBtnFlyHold = 42002
	/*MavCmdSoloBtnPauseClick - PAUSE button has been clicked. */
	MavCmdSoloBtnPauseClick = 42003
	/*MavCmdFixedMagCal - Magnetometer calibration based on fixed position
	  in earth field given by inclination, declination and intensity. */
	MavCmdFixedMagCal = 42004
	/*MavCmdFixedMagCalField - Magnetometer calibration based on fixed expected field values in milliGauss. */
	MavCmdFixedMagCalField = 42005
	/*MavCmdFixedMagCalYaw - Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. */
	MavCmdFixedMagCalYaw = 42006
	/*MavCmdDoStartMagCal - Initiate a magnetometer calibration. */
	MavCmdDoStartMagCal = 42424
	/*MavCmdDoAcceptMagCal - Initiate a magnetometer calibration. */
	MavCmdDoAcceptMagCal = 42425
	/*MavCmdDoCancelMagCal - Cancel a running magnetometer calibration. */
	MavCmdDoCancelMagCal = 42426
	/*MavCmdSetFactoryTestMode - Command autopilot to get into factory test/diagnostic mode. */
	MavCmdSetFactoryTestMode = 42427
	/*MavCmdDoSendBanner - Reply with the version banner. */
	MavCmdDoSendBanner = 42428
	/*MavCmdAccelcalVehiclePos - Used when doing accelerometer calibration. When sent to the GCS tells it what position to put the vehicle in. When sent to the vehicle says what position the vehicle is in. */
	MavCmdAccelcalVehiclePos = 42429
	/*MavCmdGimbalReset - Causes the gimbal to reset and boot as if it was just powered on. */
	MavCmdGimbalReset = 42501
	/*MavCmdGimbalAxisCalibrationStatus - Reports progress and success or failure of gimbal axis calibration procedure. */
	MavCmdGimbalAxisCalibrationStatus = 42502
	/*MavCmdGimbalRequestAxisCalibration - Starts commutation calibration on the gimbal. */
	MavCmdGimbalRequestAxisCalibration = 42503
	/*MavCmdGimbalFullReset - Erases gimbal application and parameters. */
	MavCmdGimbalFullReset = 42505
	/*MavCmdDoWinch - Command to operate winch. */
	MavCmdDoWinch = 42600
	/*MavCmdFlashBootloader - Update the bootloader */
	MavCmdFlashBootloader = 42650
	/*MavCmdBatteryReset - Reset battery capacity for batteries that accumulate consumed battery via integration. */
	MavCmdBatteryReset = 42651
	/*MavCmdEnumEnd -  */
	MavCmdEnumEnd = 42652
)

MAV_CMD - 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. See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries

View Source
const (
	/*LimitsInit - Pre-initialization. */
	LimitsInit = 0
	/*LimitsDisabled - Disabled. */
	LimitsDisabled = 1
	/*LimitsEnabled - Checking limits. */
	LimitsEnabled = 2
	/*LimitsTriggered - A limit has been breached. */
	LimitsTriggered = 3
	/*LimitsRecovering - Taking action e.g. Return/RTL. */
	LimitsRecovering = 4
	/*LimitsRecovered - We're no longer in breach of a limit. */
	LimitsRecovered = 5
	/*LimitsStateEnumEnd -  */
	LimitsStateEnumEnd = 6
)

LIMITS_STATE -

View Source
const (
	/*LimitGPSlock - Pre-initialization. */
	LimitGPSlock = 1
	/*LimitGeofence - Disabled. */
	LimitGeofence = 2
	/*LimitAltitude - Checking limits. */
	LimitAltitude = 4
	/*LimitModuleEnumEnd -  */
	LimitModuleEnumEnd = 5
)

LIMIT_MODULE -

View Source
const (
	/*FavorableWind - Flag set when requiring favorable winds for landing. */
	FavorableWind = 1
	/*LandImmediately - 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. */
	LandImmediately = 2
	/*RallyFlagsEnumEnd -  */
	RallyFlagsEnumEnd = 3
)

RALLY_FLAGS - Flags in RALLY_POINT message.

View Source
const (
	/*GripperActionRelease - Gripper release cargo. */
	GripperActionRelease = 0
	/*GripperActionGrab - Gripper grab onto cargo. */
	GripperActionGrab = 1
	/*GripperActionsEnumEnd -  */
	GripperActionsEnumEnd = 2
)

GRIPPER_ACTIONS - Gripper actions.

View Source
const (
	/*WinchRelaxed - Relax winch. */
	WinchRelaxed = 0
	/*WinchRelativeLengthControl - Winch unwinds or winds specified length of cable optionally using specified rate. */
	WinchRelativeLengthControl = 1
	/*WinchRateControl - Winch unwinds or winds cable at specified rate in meters/seconds. */
	WinchRateControl = 2
	/*WinchActionsEnumEnd -  */
	WinchActionsEnumEnd = 3
)

WINCH_ACTIONS - Winch actions.

View Source
const (
	/*CameraStatusTypeHeartbeat - Camera heartbeat, announce camera component ID at 1Hz. */
	CameraStatusTypeHeartbeat = 0
	/*CameraStatusTypeTrigger - Camera image triggered. */
	CameraStatusTypeTrigger = 1
	/*CameraStatusTypeDisconnect - Camera connection lost. */
	CameraStatusTypeDisconnect = 2
	/*CameraStatusTypeError - Camera unknown error. */
	CameraStatusTypeError = 3
	/*CameraStatusTypeLowbatt - Camera battery low. Parameter p1 shows reported voltage. */
	CameraStatusTypeLowbatt = 4
	/*CameraStatusTypeLowstore - Camera storage low. Parameter p1 shows reported shots remaining. */
	CameraStatusTypeLowstore = 5
	/*CameraStatusTypeLowstorev - Camera storage low. Parameter p1 shows reported video minutes remaining. */
	CameraStatusTypeLowstorev = 6
	/*CameraStatusTypesEnumEnd -  */
	CameraStatusTypesEnumEnd = 7
)

CAMERA_STATUS_TYPES -

View Source
const (
	/*CameraFeedbackPhoto - Shooting photos, not video. */
	CameraFeedbackPhoto = 0
	/*CameraFeedbackVIDeo - Shooting video, not stills. */
	CameraFeedbackVIDeo = 1
	/*CameraFeedbackBadexposure - Unable to achieve requested exposure (e.g. shutter speed too low). */
	CameraFeedbackBadexposure = 2
	/*CameraFeedbackClosedloop - Closed loop feedback from camera, we know for sure it has successfully taken a picture. */
	CameraFeedbackClosedloop = 3
	/*CameraFeedbackOpenloop - Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture. */
	CameraFeedbackOpenloop = 4
	/*CameraFeedbackFlagsEnumEnd -  */
	CameraFeedbackFlagsEnumEnd = 5
)

CAMERA_FEEDBACK_FLAGS -

View Source
const (
	/*MavModeGimbalUninitialized - Gimbal is powered on but has not started initializing yet. */
	MavModeGimbalUninitialized = 0
	/*MavModeGimbalCalibratingPitch - Gimbal is currently running calibration on the pitch axis. */
	MavModeGimbalCalibratingPitch = 1
	/*MavModeGimbalCalibratingRoll - Gimbal is currently running calibration on the roll axis. */
	MavModeGimbalCalibratingRoll = 2
	/*MavModeGimbalCalibratingYaw - Gimbal is currently running calibration on the yaw axis. */
	MavModeGimbalCalibratingYaw = 3
	/*MavModeGimbalInitialized - Gimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter. */
	MavModeGimbalInitialized = 4
	/*MavModeGimbalActive - Gimbal is actively stabilizing. */
	MavModeGimbalActive = 5
	/*MavModeGimbalRateCmdTimeout - 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. */
	MavModeGimbalRateCmdTimeout = 6
	/*MavModeGimbalEnumEnd -  */
	MavModeGimbalEnumEnd = 7
)

MAV_MODE_GIMBAL -

View Source
const (
	/*GimbalAxisYaw - Gimbal yaw axis. */
	GimbalAxisYaw = 0
	/*GimbalAxisPitch - Gimbal pitch axis. */
	GimbalAxisPitch = 1
	/*GimbalAxisRoll - Gimbal roll axis. */
	GimbalAxisRoll = 2
	/*GimbalAxisEnumEnd -  */
	GimbalAxisEnumEnd = 3
)

GIMBAL_AXIS -

View Source
const (
	/*GimbalAxisCalibrationStatusInProgress - Axis calibration is in progress. */
	GimbalAxisCalibrationStatusInProgress = 0
	/*GimbalAxisCalibrationStatusSucceeded - Axis calibration succeeded. */
	GimbalAxisCalibrationStatusSucceeded = 1
	/*GimbalAxisCalibrationStatusFailed - Axis calibration failed. */
	GimbalAxisCalibrationStatusFailed = 2
	/*GimbalAxisCalibrationStatusEnumEnd -  */
	GimbalAxisCalibrationStatusEnumEnd = 3
)

GIMBAL_AXIS_CALIBRATION_STATUS -

View Source
const (
	/*GimbalAxisCalibrationRequiredUnknown - Whether or not this axis requires calibration is unknown at this time. */
	GimbalAxisCalibrationRequiredUnknown = 0
	/*GimbalAxisCalibrationRequiredTrue - This axis requires calibration. */
	GimbalAxisCalibrationRequiredTrue = 1
	/*GimbalAxisCalibrationRequiredFalse - This axis does not require calibration. */
	GimbalAxisCalibrationRequiredFalse = 2
	/*GimbalAxisCalibrationRequiredEnumEnd -  */
	GimbalAxisCalibrationRequiredEnumEnd = 3
)

GIMBAL_AXIS_CALIBRATION_REQUIRED -

View Source
const (
	/*GoproHeartbeatStatusDisconnected - No GoPro connected. */
	GoproHeartbeatStatusDisconnected = 0
	/*GoproHeartbeatStatusIncompatible - The detected GoPro is not HeroBus compatible. */
	GoproHeartbeatStatusIncompatible = 1
	/*GoproHeartbeatStatusConnected - A HeroBus compatible GoPro is connected. */
	GoproHeartbeatStatusConnected = 2
	/*GoproHeartbeatStatusError - An unrecoverable error was encountered with the connected GoPro, it may require a power cycle. */
	GoproHeartbeatStatusError = 3
	/*GoproHeartbeatStatusEnumEnd -  */
	GoproHeartbeatStatusEnumEnd = 4
)

GOPRO_HEARTBEAT_STATUS -

View Source
const (
	/*GoproFlagRecording - GoPro is currently recording. */
	GoproFlagRecording = 1
	/*GoproHeartbeatFlagsEnumEnd -  */
	GoproHeartbeatFlagsEnumEnd = 2
)

GOPRO_HEARTBEAT_FLAGS -

View Source
const (
	/*GoproRequestSuccess - The write message with ID indicated succeeded. */
	GoproRequestSuccess = 0
	/*GoproRequestFailed - The write message with ID indicated failed. */
	GoproRequestFailed = 1
	/*GoproRequestStatusEnumEnd -  */
	GoproRequestStatusEnumEnd = 2
)

GOPRO_REQUEST_STATUS -

View Source
const (
	/*GoproCommandPower - (Get/Set). */
	GoproCommandPower = 0
	/*GoproCommandCaptureMode - (Get/Set). */
	GoproCommandCaptureMode = 1
	/*GoproCommandShutter - (___/Set). */
	GoproCommandShutter = 2
	/*GoproCommandBattery - (Get/___). */
	GoproCommandBattery = 3
	/*GoproCommandModel - (Get/___). */
	GoproCommandModel = 4
	/*GoproCommandVIDeoSettings - (Get/Set). */
	GoproCommandVIDeoSettings = 5
	/*GoproCommandLowLight - (Get/Set). */
	GoproCommandLowLight = 6
	/*GoproCommandPhotoResolution - (Get/Set). */
	GoproCommandPhotoResolution = 7
	/*GoproCommandPhotoBurstRate - (Get/Set). */
	GoproCommandPhotoBurstRate = 8
	/*GoproCommandProtune - (Get/Set). */
	GoproCommandProtune = 9
	/*GoproCommandProtuneWhiteBalance - (Get/Set) Hero 3+ Only. */
	GoproCommandProtuneWhiteBalance = 10
	/*GoproCommandProtuneColour - (Get/Set) Hero 3+ Only. */
	GoproCommandProtuneColour = 11
	/*GoproCommandProtuneGain - (Get/Set) Hero 3+ Only. */
	GoproCommandProtuneGain = 12
	/*GoproCommandProtuneSharpness - (Get/Set) Hero 3+ Only. */
	GoproCommandProtuneSharpness = 13
	/*GoproCommandProtuneExposure - (Get/Set) Hero 3+ Only. */
	GoproCommandProtuneExposure = 14
	/*GoproCommandTime - (Get/Set). */
	GoproCommandTime = 15
	/*GoproCommandCharging - (Get/Set). */
	GoproCommandCharging = 16
	/*GoproCommandEnumEnd -  */
	GoproCommandEnumEnd = 17
)

GOPRO_COMMAND -

View Source
const (
	/*GoproCaptureModeVIDeo - Video mode. */
	GoproCaptureModeVIDeo = 0
	/*GoproCaptureModePhoto - Photo mode. */
	GoproCaptureModePhoto = 1
	/*GoproCaptureModeBurst - Burst mode, Hero 3+ only. */
	GoproCaptureModeBurst = 2
	/*GoproCaptureModeTimeLapse - Time lapse mode, Hero 3+ only. */
	GoproCaptureModeTimeLapse = 3
	/*GoproCaptureModeMultiShot - Multi shot mode, Hero 4 only. */
	GoproCaptureModeMultiShot = 4
	/*GoproCaptureModePlayback - Playback mode, Hero 4 only, silver only except when LCD or HDMI is connected to black. */
	GoproCaptureModePlayback = 5
	/*GoproCaptureModeSetup - Playback mode, Hero 4 only. */
	GoproCaptureModeSetup = 6
	/*GoproCaptureModeUnknown - Mode not yet known. */
	GoproCaptureModeUnknown = 255
	/*GoproCaptureModeEnumEnd -  */
	GoproCaptureModeEnumEnd = 256
)

GOPRO_CAPTURE_MODE -

View Source
const (
	/*GoproResolution480P - 848 x 480 (480p). */
	GoproResolution480P = 0
	/*GoproResolution720P - 1280 x 720 (720p). */
	GoproResolution720P = 1
	/*GoproResolution960P - 1280 x 960 (960p). */
	GoproResolution960P = 2
	/*GoproResolution1080P - 1920 x 1080 (1080p). */
	GoproResolution1080P = 3
	/*GoproResolution1440P - 1920 x 1440 (1440p). */
	GoproResolution1440P = 4
	/*GoproResolution27K179 - 2704 x 1440 (2.7k-17:9). */
	GoproResolution27K179 = 5
	/*GoproResolution27K169 - 2704 x 1524 (2.7k-16:9). */
	GoproResolution27K169 = 6
	/*GoproResolution27K43 - 2704 x 2028 (2.7k-4:3). */
	GoproResolution27K43 = 7
	/*GoproResolution4K169 - 3840 x 2160 (4k-16:9). */
	GoproResolution4K169 = 8
	/*GoproResolution4K179 - 4096 x 2160 (4k-17:9). */
	GoproResolution4K179 = 9
	/*GoproResolution720PSuperview - 1280 x 720 (720p-SuperView). */
	GoproResolution720PSuperview = 10
	/*GoproResolution1080PSuperview - 1920 x 1080 (1080p-SuperView). */
	GoproResolution1080PSuperview = 11
	/*GoproResolution27KSuperview - 2704 x 1520 (2.7k-SuperView). */
	GoproResolution27KSuperview = 12
	/*GoproResolution4KSuperview - 3840 x 2160 (4k-SuperView). */
	GoproResolution4KSuperview = 13
	/*GoproResolutionEnumEnd -  */
	GoproResolutionEnumEnd = 14
)

GOPRO_RESOLUTION -

View Source
const (
	/*GoproFrameRate12 - 12 FPS. */
	GoproFrameRate12 = 0
	/*GoproFrameRate15 - 15 FPS. */
	GoproFrameRate15 = 1
	/*GoproFrameRate24 - 24 FPS. */
	GoproFrameRate24 = 2
	/*GoproFrameRate25 - 25 FPS. */
	GoproFrameRate25 = 3
	/*GoproFrameRate30 - 30 FPS. */
	GoproFrameRate30 = 4
	/*GoproFrameRate48 - 48 FPS. */
	GoproFrameRate48 = 5
	/*GoproFrameRate50 - 50 FPS. */
	GoproFrameRate50 = 6
	/*GoproFrameRate60 - 60 FPS. */
	GoproFrameRate60 = 7
	/*GoproFrameRate80 - 80 FPS. */
	GoproFrameRate80 = 8
	/*GoproFrameRate90 - 90 FPS. */
	GoproFrameRate90 = 9
	/*GoproFrameRate100 - 100 FPS. */
	GoproFrameRate100 = 10
	/*GoproFrameRate120 - 120 FPS. */
	GoproFrameRate120 = 11
	/*GoproFrameRate240 - 240 FPS. */
	GoproFrameRate240 = 12
	/*GoproFrameRate125 - 12.5 FPS. */
	GoproFrameRate125 = 13
	/*GoproFrameRateEnumEnd -  */
	GoproFrameRateEnumEnd = 14
)

GOPRO_FRAME_RATE -

View Source
const (
	/*GoproFieldOfViewWIDe - 0x00: Wide. */
	GoproFieldOfViewWIDe = 0
	/*GoproFieldOfViewMedium - 0x01: Medium. */
	GoproFieldOfViewMedium = 1
	/*GoproFieldOfViewNarrow - 0x02: Narrow. */
	GoproFieldOfViewNarrow = 2
	/*GoproFieldOfViewEnumEnd -  */
	GoproFieldOfViewEnumEnd = 3
)

GOPRO_FIELD_OF_VIEW -

View Source
const (
	/*GoproVIDeoSettingsTvMode - 0=NTSC, 1=PAL. */
	GoproVIDeoSettingsTvMode = 1
	/*GoproVIDeoSettingsFlagsEnumEnd -  */
	GoproVIDeoSettingsFlagsEnumEnd = 2
)

GOPRO_VIDEO_SETTINGS_FLAGS -

View Source
const (
	/*GoproPhotoResolution5MpMedium - 5MP Medium. */
	GoproPhotoResolution5MpMedium = 0
	/*GoproPhotoResolution7MpMedium - 7MP Medium. */
	GoproPhotoResolution7MpMedium = 1
	/*GoproPhotoResolution7MpWIDe - 7MP Wide. */
	GoproPhotoResolution7MpWIDe = 2
	/*GoproPhotoResolution10MpWIDe - 10MP Wide. */
	GoproPhotoResolution10MpWIDe = 3
	/*GoproPhotoResolution12MpWIDe - 12MP Wide. */
	GoproPhotoResolution12MpWIDe = 4
	/*GoproPhotoResolutionEnumEnd -  */
	GoproPhotoResolutionEnumEnd = 5
)

GOPRO_PHOTO_RESOLUTION -

View Source
const (
	/*GoproProtuneWhiteBalanceAuto - Auto. */
	GoproProtuneWhiteBalanceAuto = 0
	/*GoproProtuneWhiteBalance3000K - 3000K. */
	GoproProtuneWhiteBalance3000K = 1
	/*GoproProtuneWhiteBalance5500K - 5500K. */
	GoproProtuneWhiteBalance5500K = 2
	/*GoproProtuneWhiteBalance6500K - 6500K. */
	GoproProtuneWhiteBalance6500K = 3
	/*GoproProtuneWhiteBalanceRaw - Camera Raw. */
	GoproProtuneWhiteBalanceRaw = 4
	/*GoproProtuneWhiteBalanceEnumEnd -  */
	GoproProtuneWhiteBalanceEnumEnd = 5
)

GOPRO_PROTUNE_WHITE_BALANCE -

View Source
const (
	/*GoproProtuneColourStandard - Auto. */
	GoproProtuneColourStandard = 0
	/*GoproProtuneColourNeutral - Neutral. */
	GoproProtuneColourNeutral = 1
	/*GoproProtuneColourEnumEnd -  */
	GoproProtuneColourEnumEnd = 2
)

GOPRO_PROTUNE_COLOUR -

View Source
const (
	/*GoproProtuneGain400 - ISO 400. */
	GoproProtuneGain400 = 0
	/*GoproProtuneGain800 - ISO 800 (Only Hero 4). */
	GoproProtuneGain800 = 1
	/*GoproProtuneGain1600 - ISO 1600. */
	GoproProtuneGain1600 = 2
	/*GoproProtuneGain3200 - ISO 3200 (Only Hero 4). */
	GoproProtuneGain3200 = 3
	/*GoproProtuneGain6400 - ISO 6400. */
	GoproProtuneGain6400 = 4
	/*GoproProtuneGainEnumEnd -  */
	GoproProtuneGainEnumEnd = 5
)

GOPRO_PROTUNE_GAIN -

View Source
const (
	/*GoproProtuneSharpnessLow - Low Sharpness. */
	GoproProtuneSharpnessLow = 0
	/*GoproProtuneSharpnessMedium - Medium Sharpness. */
	GoproProtuneSharpnessMedium = 1
	/*GoproProtuneSharpnessHigh - High Sharpness. */
	GoproProtuneSharpnessHigh = 2
	/*GoproProtuneSharpnessEnumEnd -  */
	GoproProtuneSharpnessEnumEnd = 3
)

GOPRO_PROTUNE_SHARPNESS -

View Source
const (
	/*GoproProtuneExposureNeg50 - -5.0 EV (Hero 3+ Only). */
	GoproProtuneExposureNeg50 = 0
	/*GoproProtuneExposureNeg45 - -4.5 EV (Hero 3+ Only). */
	GoproProtuneExposureNeg45 = 1
	/*GoproProtuneExposureNeg40 - -4.0 EV (Hero 3+ Only). */
	GoproProtuneExposureNeg40 = 2
	/*GoproProtuneExposureNeg35 - -3.5 EV (Hero 3+ Only). */
	GoproProtuneExposureNeg35 = 3
	/*GoproProtuneExposureNeg30 - -3.0 EV (Hero 3+ Only). */
	GoproProtuneExposureNeg30 = 4
	/*GoproProtuneExposureNeg25 - -2.5 EV (Hero 3+ Only). */
	GoproProtuneExposureNeg25 = 5
	/*GoproProtuneExposureNeg20 - -2.0 EV. */
	GoproProtuneExposureNeg20 = 6
	/*GoproProtuneExposureNeg15 - -1.5 EV. */
	GoproProtuneExposureNeg15 = 7
	/*GoproProtuneExposureNeg10 - -1.0 EV. */
	GoproProtuneExposureNeg10 = 8
	/*GoproProtuneExposureNeg05 - -0.5 EV. */
	GoproProtuneExposureNeg05 = 9
	/*GoproProtuneExposureZero - 0.0 EV. */
	GoproProtuneExposureZero = 10
	/*GoproProtuneExposurePos05 - +0.5 EV. */
	GoproProtuneExposurePos05 = 11
	/*GoproProtuneExposurePos10 - +1.0 EV. */
	GoproProtuneExposurePos10 = 12
	/*GoproProtuneExposurePos15 - +1.5 EV. */
	GoproProtuneExposurePos15 = 13
	/*GoproProtuneExposurePos20 - +2.0 EV. */
	GoproProtuneExposurePos20 = 14
	/*GoproProtuneExposurePos25 - +2.5 EV (Hero 3+ Only). */
	GoproProtuneExposurePos25 = 15
	/*GoproProtuneExposurePos30 - +3.0 EV (Hero 3+ Only). */
	GoproProtuneExposurePos30 = 16
	/*GoproProtuneExposurePos35 - +3.5 EV (Hero 3+ Only). */
	GoproProtuneExposurePos35 = 17
	/*GoproProtuneExposurePos40 - +4.0 EV (Hero 3+ Only). */
	GoproProtuneExposurePos40 = 18
	/*GoproProtuneExposurePos45 - +4.5 EV (Hero 3+ Only). */
	GoproProtuneExposurePos45 = 19
	/*GoproProtuneExposurePos50 - +5.0 EV (Hero 3+ Only). */
	GoproProtuneExposurePos50 = 20
	/*GoproProtuneExposureEnumEnd -  */
	GoproProtuneExposureEnumEnd = 21
)

GOPRO_PROTUNE_EXPOSURE -

View Source
const (
	/*GoproChargingDisabled - Charging disabled. */
	GoproChargingDisabled = 0
	/*GoproChargingEnabled - Charging enabled. */
	GoproChargingEnabled = 1
	/*GoproChargingEnumEnd -  */
	GoproChargingEnumEnd = 2
)

GOPRO_CHARGING -

View Source
const (
	/*GoproModelUnknown - Unknown gopro model. */
	GoproModelUnknown = 0
	/*GoproModelHero3PlusSilver - Hero 3+ Silver (HeroBus not supported by GoPro). */
	GoproModelHero3PlusSilver = 1
	/*GoproModelHero3PlusBlack - Hero 3+ Black. */
	GoproModelHero3PlusBlack = 2
	/*GoproModelHero4Silver - Hero 4 Silver. */
	GoproModelHero4Silver = 3
	/*GoproModelHero4Black - Hero 4 Black. */
	GoproModelHero4Black = 4
	/*GoproModelEnumEnd -  */
	GoproModelEnumEnd = 5
)

GOPRO_MODEL -

View Source
const (
	/*GoproBurstRate3In1Second - 3 Shots / 1 Second. */
	GoproBurstRate3In1Second = 0
	/*GoproBurstRate5In1Second - 5 Shots / 1 Second. */
	GoproBurstRate5In1Second = 1
	/*GoproBurstRate10In1Second - 10 Shots / 1 Second. */
	GoproBurstRate10In1Second = 2
	/*GoproBurstRate10In2Second - 10 Shots / 2 Second. */
	GoproBurstRate10In2Second = 3
	/*GoproBurstRate10In3Second - 10 Shots / 3 Second (Hero 4 Only). */
	GoproBurstRate10In3Second = 4
	/*GoproBurstRate30In1Second - 30 Shots / 1 Second. */
	GoproBurstRate30In1Second = 5
	/*GoproBurstRate30In2Second - 30 Shots / 2 Second. */
	GoproBurstRate30In2Second = 6
	/*GoproBurstRate30In3Second - 30 Shots / 3 Second. */
	GoproBurstRate30In3Second = 7
	/*GoproBurstRate30In6Second - 30 Shots / 6 Second. */
	GoproBurstRate30In6Second = 8
	/*GoproBurstRateEnumEnd -  */
	GoproBurstRateEnumEnd = 9
)

GOPRO_BURST_RATE -

View Source
const (
	/*LedControlPatternOff - LED patterns off (return control to regular vehicle control). */
	LedControlPatternOff = 0
	/*LedControlPatternFirmwareupdate - LEDs show pattern during firmware update. */
	LedControlPatternFirmwareupdate = 1
	/*LedControlPatternCustom - Custom Pattern using custom bytes fields. */
	LedControlPatternCustom = 255
	/*LedControlPatternEnumEnd -  */
	LedControlPatternEnumEnd = 256
)

LED_CONTROL_PATTERN -

View Source
const (
	/*EKFAttitude - Set if EKF's attitude estimate is good. */
	EKFAttitude = 1
	/*EKFVelocityHoriz - Set if EKF's horizontal velocity estimate is good. */
	EKFVelocityHoriz = 2
	/*EKFVelocityVert - Set if EKF's vertical velocity estimate is good. */
	EKFVelocityVert = 4
	/*EKFPosHorizRel - Set if EKF's horizontal position (relative) estimate is good. */
	EKFPosHorizRel = 8
	/*EKFPosHorizAbs - Set if EKF's horizontal position (absolute) estimate is good. */
	EKFPosHorizAbs = 16
	/*EKFPosVertAbs - Set if EKF's vertical position (absolute) estimate is good. */
	EKFPosVertAbs = 32
	/*EKFPosVertAgl - Set if EKF's vertical position (above ground) estimate is good. */
	EKFPosVertAgl = 64
	/*EKFConstPosMode - EKF is in constant position mode and does not know it's absolute or relative position. */
	EKFConstPosMode = 128
	/*EKFPredPosHorizRel - Set if EKF's predicted horizontal position (relative) estimate is good. */
	EKFPredPosHorizRel = 256
	/*EKFPredPosHorizAbs - Set if EKF's predicted horizontal position (absolute) estimate is good. */
	EKFPredPosHorizAbs = 512
	/*EKFStatusFlagsEnumEnd -  */
	EKFStatusFlagsEnumEnd = 513
)

EKF_STATUS_FLAGS - Flags in EKF_STATUS message.

View Source
const (
	/*PIDTuningRoll -  */
	PIDTuningRoll = 1
	/*PIDTuningPitch -  */
	PIDTuningPitch = 2
	/*PIDTuningYaw -  */
	PIDTuningYaw = 3
	/*PIDTuningAccz -  */
	PIDTuningAccz = 4
	/*PIDTuningSteer -  */
	PIDTuningSteer = 5
	/*PIDTuningLanding -  */
	PIDTuningLanding = 6
	/*PIDTuningAxisEnumEnd -  */
	PIDTuningAxisEnumEnd = 7
)

PID_TUNING_AXIS -

View Source
const (
	/*MagCalNotStarted -  */
	MagCalNotStarted = 0
	/*MagCalWaitingToStart -  */
	MagCalWaitingToStart = 1
	/*MagCalRunningStepOne -  */
	MagCalRunningStepOne = 2
	/*MagCalRunningStepTwo -  */
	MagCalRunningStepTwo = 3
	/*MagCalSuccess -  */
	MagCalSuccess = 4
	/*MagCalFailed -  */
	MagCalFailed = 5
	/*MagCalBadOrientation -  */
	MagCalBadOrientation = 6
	/*MagCalBadRadius -  */
	MagCalBadRadius = 7
	/*MagCalStatusEnumEnd -  */
	MagCalStatusEnumEnd = 8
)

MAG_CAL_STATUS -

View Source
const (
	/*MavRemoteLogDataBlockStop - UAV to stop sending DataFlash blocks. */
	MavRemoteLogDataBlockStop = 2147483645
	/*MavRemoteLogDataBlockStart - UAV to start sending DataFlash blocks. */
	MavRemoteLogDataBlockStart = 2147483646
	/*MavRemoteLogDataBlockCommandsEnumEnd -  */
	MavRemoteLogDataBlockCommandsEnumEnd = 2147483647
)

MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS - Special ACK block numbers control activation of dataflash log streaming.

View Source
const (
	/*MavRemoteLogDataBlockNack - This block has NOT been received. */
	MavRemoteLogDataBlockNack = 0
	/*MavRemoteLogDataBlockAck - This block has been received. */
	MavRemoteLogDataBlockAck = 1
	/*MavRemoteLogDataBlockStatusesEnumEnd -  */
	MavRemoteLogDataBlockStatusesEnumEnd = 2
)

MAV_REMOTE_LOG_DATA_BLOCK_STATUSES - Possible remote log data block statuses.

View Source
const (
	/*DeviceOpBustypeI2C - I2C Device operation. */
	DeviceOpBustypeI2C = 0
	/*DeviceOpBustypeSpi - SPI Device operation. */
	DeviceOpBustypeSpi = 1
	/*DeviceOpBustypeEnumEnd -  */
	DeviceOpBustypeEnumEnd = 2
)

DEVICE_OP_BUSTYPE - Bus types for device operations.

View Source
const (
	/*DeepstallStageFlyToLanding - Flying to the landing point. */
	DeepstallStageFlyToLanding = 0
	/*DeepstallStageEstimateWind - Building an estimate of the wind. */
	DeepstallStageEstimateWind = 1
	/*DeepstallStageWaitForBreakout - Waiting to breakout of the loiter to fly the approach. */
	DeepstallStageWaitForBreakout = 2
	/*DeepstallStageFlyToARC - Flying to the first arc point to turn around to the landing point. */
	DeepstallStageFlyToARC = 3
	/*DeepstallStageARC - Turning around back to the deepstall landing point. */
	DeepstallStageARC = 4
	/*DeepstallStageApproach - Approaching the landing point. */
	DeepstallStageApproach = 5
	/*DeepstallStageLand - Stalling and steering towards the land point. */
	DeepstallStageLand = 6
	/*DeepstallStageEnumEnd -  */
	DeepstallStageEnumEnd = 7
)

DEEPSTALL_STAGE - Deepstall flight stage.

View Source
const (
	/*PlaneModeManual -  */
	PlaneModeManual = 0
	/*PlaneModeCiRCle -  */
	PlaneModeCiRCle = 1
	/*PlaneModeStabilize -  */
	PlaneModeStabilize = 2
	/*PlaneModeTraining -  */
	PlaneModeTraining = 3
	/*PlaneModeAcro -  */
	PlaneModeAcro = 4
	/*PlaneModeFlyByWireA -  */
	PlaneModeFlyByWireA = 5
	/*PlaneModeFlyByWireB -  */
	PlaneModeFlyByWireB = 6
	/*PlaneModeCruise -  */
	PlaneModeCruise = 7
	/*PlaneModeAutotune -  */
	PlaneModeAutotune = 8
	/*PlaneModeAuto -  */
	PlaneModeAuto = 10
	/*PlaneModeRtl -  */
	PlaneModeRtl = 11
	/*PlaneModeLoiter -  */
	PlaneModeLoiter = 12
	/*PlaneModeTakeoff -  */
	PlaneModeTakeoff = 13
	/*PlaneModeAvoIDAdsb -  */
	PlaneModeAvoIDAdsb = 14
	/*PlaneModeGUIDed -  */
	PlaneModeGUIDed = 15
	/*PlaneModeInitializing -  */
	PlaneModeInitializing = 16
	/*PlaneModeQstabilize -  */
	PlaneModeQstabilize = 17
	/*PlaneModeQhover -  */
	PlaneModeQhover = 18
	/*PlaneModeQloiter -  */
	PlaneModeQloiter = 19
	/*PlaneModeQland -  */
	PlaneModeQland = 20
	/*PlaneModeQrtl -  */
	PlaneModeQrtl = 21
	/*PlaneModeQautotune -  */
	PlaneModeQautotune = 22
	/*PlaneModeEnumEnd -  */
	PlaneModeEnumEnd = 23
)

PLANE_MODE - A mapping of plane flight modes for custom_mode field of heartbeat.

View Source
const (
	/*CopterModeStabilize -  */
	CopterModeStabilize = 0
	/*CopterModeAcro -  */
	CopterModeAcro = 1
	/*CopterModeAltHold -  */
	CopterModeAltHold = 2
	/*CopterModeAuto -  */
	CopterModeAuto = 3
	/*CopterModeGUIDed -  */
	CopterModeGUIDed = 4
	/*CopterModeLoiter -  */
	CopterModeLoiter = 5
	/*CopterModeRtl -  */
	CopterModeRtl = 6
	/*CopterModeCiRCle -  */
	CopterModeCiRCle = 7
	/*CopterModeLand -  */
	CopterModeLand = 9
	/*CopterModeDrift -  */
	CopterModeDrift = 11
	/*CopterModeSport -  */
	CopterModeSport = 13
	/*CopterModeFlip -  */
	CopterModeFlip = 14
	/*CopterModeAutotune -  */
	CopterModeAutotune = 15
	/*CopterModePoshold -  */
	CopterModePoshold = 16
	/*CopterModeBrake -  */
	CopterModeBrake = 17
	/*CopterModeThrow -  */
	CopterModeThrow = 18
	/*CopterModeAvoIDAdsb -  */
	CopterModeAvoIDAdsb = 19
	/*CopterModeGUIDedNoGPS -  */
	CopterModeGUIDedNoGPS = 20
	/*CopterModeSmartRtl -  */
	CopterModeSmartRtl = 21
	/*CopterModeEnumEnd -  */
	CopterModeEnumEnd = 22
)

COPTER_MODE - A mapping of copter flight modes for custom_mode field of heartbeat.

View Source
const (
	/*SubModeStabilize -  */
	SubModeStabilize = 0
	/*SubModeAcro -  */
	SubModeAcro = 1
	/*SubModeAltHold -  */
	SubModeAltHold = 2
	/*SubModeAuto -  */
	SubModeAuto = 3
	/*SubModeGUIDed -  */
	SubModeGUIDed = 4
	/*SubModeCiRCle -  */
	SubModeCiRCle = 7
	/*SubModeSurface -  */
	SubModeSurface = 9
	/*SubModePoshold -  */
	SubModePoshold = 16
	/*SubModeManual -  */
	SubModeManual = 19
	/*SubModeEnumEnd -  */
	SubModeEnumEnd = 20
)

SUB_MODE - A mapping of sub flight modes for custom_mode field of heartbeat.

View Source
const (
	/*RoverModeManual -  */
	RoverModeManual = 0
	/*RoverModeAcro -  */
	RoverModeAcro = 1
	/*RoverModeSteering -  */
	RoverModeSteering = 3
	/*RoverModeHold -  */
	RoverModeHold = 4
	/*RoverModeLoiter -  */
	RoverModeLoiter = 5
	/*RoverModeAuto -  */
	RoverModeAuto = 10
	/*RoverModeRtl -  */
	RoverModeRtl = 11
	/*RoverModeSmartRtl -  */
	RoverModeSmartRtl = 12
	/*RoverModeGUIDed -  */
	RoverModeGUIDed = 15
	/*RoverModeInitializing -  */
	RoverModeInitializing = 16
	/*RoverModeEnumEnd -  */
	RoverModeEnumEnd = 17
)

ROVER_MODE - A mapping of rover flight modes for custom_mode field of heartbeat.

View Source
const (
	/*TrackerModeManual -  */
	TrackerModeManual = 0
	/*TrackerModeStop -  */
	TrackerModeStop = 1
	/*TrackerModeScan -  */
	TrackerModeScan = 2
	/*TrackerModeServoTest -  */
	TrackerModeServoTest = 3
	/*TrackerModeAuto -  */
	TrackerModeAuto = 10
	/*TrackerModeInitializing -  */
	TrackerModeInitializing = 16
	/*TrackerModeEnumEnd -  */
	TrackerModeEnumEnd = 17
)

TRACKER_MODE - A mapping of antenna tracker flight modes for custom_mode field of heartbeat.

Variables

This section is empty.

Functions

This section is empty.

Types

type AHRS

type AHRS struct {
	/*Omegaix X gyro drift estimate. */
	Omegaix float32
	/*Omegaiy Y gyro drift estimate. */
	Omegaiy float32
	/*Omegaiz Z gyro drift estimate. */
	Omegaiz float32
	/*AccelWeight Average accel_weight. */
	AccelWeight float32
	/*RenormVal Average renormalisation value. */
	RenormVal float32
	/*ErrorRp Average error_roll_pitch value. */
	ErrorRp float32
	/*ErrorYaw Average error_yaw value. */
	ErrorYaw float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

AHRS Status of DCM attitude estimator.

func (*AHRS) GetDialect

func (m *AHRS) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*AHRS) GetID

func (m *AHRS) GetID() uint32

GetID gets the ID of the Message

func (*AHRS) GetMessageName

func (m *AHRS) GetMessageName() string

GetMessageName gets the name of the Message

func (*AHRS) GetVersion

func (m *AHRS) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*AHRS) HasExtensionFields

func (m *AHRS) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*AHRS) Read

func (m *AHRS) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*AHRS) String

func (m *AHRS) String() string

func (*AHRS) Write

func (m *AHRS) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type AHRS2

type AHRS2 struct {
	/*Roll Roll angle. */
	Roll float32
	/*Pitch Pitch angle. */
	Pitch float32
	/*Yaw Yaw angle. */
	Yaw float32
	/*Altitude Altitude (MSL). */
	Altitude float32
	/*Lat Latitude. */
	Lat int32
	/*Lng Longitude. */
	Lng int32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

AHRS2 Status of secondary AHRS filter if available.

func (*AHRS2) GetDialect

func (m *AHRS2) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*AHRS2) GetID

func (m *AHRS2) GetID() uint32

GetID gets the ID of the Message

func (*AHRS2) GetMessageName

func (m *AHRS2) GetMessageName() string

GetMessageName gets the name of the Message

func (*AHRS2) GetVersion

func (m *AHRS2) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*AHRS2) HasExtensionFields

func (m *AHRS2) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*AHRS2) Read

func (m *AHRS2) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*AHRS2) String

func (m *AHRS2) String() string

func (*AHRS2) Write

func (m *AHRS2) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type AHRS3

type AHRS3 struct {
	/*Roll Roll angle. */
	Roll float32
	/*Pitch Pitch angle. */
	Pitch float32
	/*Yaw Yaw angle. */
	Yaw float32
	/*Altitude Altitude (MSL). */
	Altitude float32
	/*Lat Latitude. */
	Lat int32
	/*Lng Longitude. */
	Lng int32
	/*V1 Test variable1. */
	V1 float32
	/*V2 Test variable2. */
	V2 float32
	/*V3 Test variable3. */
	V3 float32
	/*V4 Test variable4. */
	V4 float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

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

func (*AHRS3) GetDialect

func (m *AHRS3) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*AHRS3) GetID

func (m *AHRS3) GetID() uint32

GetID gets the ID of the Message

func (*AHRS3) GetMessageName

func (m *AHRS3) GetMessageName() string

GetMessageName gets the name of the Message

func (*AHRS3) GetVersion

func (m *AHRS3) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*AHRS3) HasExtensionFields

func (m *AHRS3) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*AHRS3) Read

func (m *AHRS3) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*AHRS3) String

func (m *AHRS3) String() string

func (*AHRS3) Write

func (m *AHRS3) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type AdapTuning

type AdapTuning struct {
	/*Desired Desired rate. */
	Desired float32
	/*Achieved Achieved rate. */
	Achieved float32
	/*Error Error between model and vehicle. */
	Error float32
	/*Theta Theta estimated state predictor. */
	Theta float32
	/*Omega Omega estimated state predictor. */
	Omega float32
	/*Sigma Sigma estimated state predictor. */
	Sigma float32
	/*ThetaDot Theta derivative. */
	ThetaDot float32
	/*OmegaDot Omega derivative. */
	OmegaDot float32
	/*SigmaDot Sigma derivative. */
	SigmaDot float32
	/*F Projection operator value. */
	F float32
	/*FDot Projection operator derivative. */
	FDot float32
	/*U u adaptive controlled output command. */
	U float32
	/*Axis Axis. */
	Axis uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

AdapTuning Adaptive Controller tuning information.

func (*AdapTuning) GetDialect

func (m *AdapTuning) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*AdapTuning) GetID

func (m *AdapTuning) GetID() uint32

GetID gets the ID of the Message

func (*AdapTuning) GetMessageName

func (m *AdapTuning) GetMessageName() string

GetMessageName gets the name of the Message

func (*AdapTuning) GetVersion

func (m *AdapTuning) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*AdapTuning) HasExtensionFields

func (m *AdapTuning) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*AdapTuning) Read

func (m *AdapTuning) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*AdapTuning) String

func (m *AdapTuning) String() string

func (*AdapTuning) Write

func (m *AdapTuning) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type AirspeedAutocal

type AirspeedAutocal struct {
	/*Vx GPS velocity north. */
	Vx float32
	/*Vy GPS velocity east. */
	Vy float32
	/*Vz GPS velocity down. */
	Vz float32
	/*DiffPressure Differential pressure. */
	DiffPressure float32
	/*Eas2Tas Estimated to true airspeed ratio. */
	Eas2Tas float32
	/*Ratio Airspeed ratio. */
	Ratio float32
	/*StateX EKF state x. */
	StateX float32
	/*StateY EKF state y. */
	StateY float32
	/*StateZ EKF state z. */
	StateZ float32
	/*Pax EKF Pax. */
	Pax float32
	/*Pby EKF Pby. */
	Pby float32
	/*Pcz EKF Pcz. */
	Pcz float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

AirspeedAutocal Airspeed auto-calibration.

func (*AirspeedAutocal) GetDialect

func (m *AirspeedAutocal) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*AirspeedAutocal) GetID

func (m *AirspeedAutocal) GetID() uint32

GetID gets the ID of the Message

func (*AirspeedAutocal) GetMessageName

func (m *AirspeedAutocal) GetMessageName() string

GetMessageName gets the name of the Message

func (*AirspeedAutocal) GetVersion

func (m *AirspeedAutocal) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*AirspeedAutocal) HasExtensionFields

func (m *AirspeedAutocal) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*AirspeedAutocal) Read

func (m *AirspeedAutocal) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*AirspeedAutocal) String

func (m *AirspeedAutocal) String() string

func (*AirspeedAutocal) Write

func (m *AirspeedAutocal) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type AoaSsa

type AoaSsa struct {
	/*TimeUsec Timestamp (since boot or Unix epoch). */
	TimeUsec uint64
	/*Aoa Angle of Attack. */
	Aoa float32
	/*Ssa Side Slip Angle. */
	Ssa float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

AoaSsa Angle of Attack and Side Slip Angle.

func (*AoaSsa) GetDialect

func (m *AoaSsa) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*AoaSsa) GetID

func (m *AoaSsa) GetID() uint32

GetID gets the ID of the Message

func (*AoaSsa) GetMessageName

func (m *AoaSsa) GetMessageName() string

GetMessageName gets the name of the Message

func (*AoaSsa) GetVersion

func (m *AoaSsa) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*AoaSsa) HasExtensionFields

func (m *AoaSsa) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*AoaSsa) Read

func (m *AoaSsa) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*AoaSsa) String

func (m *AoaSsa) String() string

func (*AoaSsa) Write

func (m *AoaSsa) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type ApAdc

type ApAdc struct {
	/*Adc1 ADC output 1. */
	Adc1 uint16
	/*Adc2 ADC output 2. */
	Adc2 uint16
	/*Adc3 ADC output 3. */
	Adc3 uint16
	/*Adc4 ADC output 4. */
	Adc4 uint16
	/*Adc5 ADC output 5. */
	Adc5 uint16
	/*Adc6 ADC output 6. */
	Adc6 uint16
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

ApAdc Raw ADC output.

func (*ApAdc) GetDialect

func (m *ApAdc) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*ApAdc) GetID

func (m *ApAdc) GetID() uint32

GetID gets the ID of the Message

func (*ApAdc) GetMessageName

func (m *ApAdc) GetMessageName() string

GetMessageName gets the name of the Message

func (*ApAdc) GetVersion

func (m *ApAdc) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*ApAdc) HasExtensionFields

func (m *ApAdc) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*ApAdc) Read

func (m *ApAdc) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*ApAdc) String

func (m *ApAdc) String() string

func (*ApAdc) Write

func (m *ApAdc) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type AutopilotVersionRequest

type AutopilotVersionRequest struct {
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

AutopilotVersionRequest Request the autopilot version from the system/component.

func (*AutopilotVersionRequest) GetDialect

func (m *AutopilotVersionRequest) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*AutopilotVersionRequest) GetID

func (m *AutopilotVersionRequest) GetID() uint32

GetID gets the ID of the Message

func (*AutopilotVersionRequest) GetMessageName

func (m *AutopilotVersionRequest) GetMessageName() string

GetMessageName gets the name of the Message

func (*AutopilotVersionRequest) GetVersion

func (m *AutopilotVersionRequest) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*AutopilotVersionRequest) HasExtensionFields

func (m *AutopilotVersionRequest) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*AutopilotVersionRequest) Read

func (m *AutopilotVersionRequest) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*AutopilotVersionRequest) String

func (m *AutopilotVersionRequest) String() string

func (*AutopilotVersionRequest) Write

func (m *AutopilotVersionRequest) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type Battery2

type Battery2 struct {
	/*Voltage Voltage. */
	Voltage uint16
	/*CurrentBattery Battery current, -1: autopilot does not measure the current. */
	CurrentBattery int16
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

Battery2 2nd Battery status

func (*Battery2) GetDialect

func (m *Battery2) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*Battery2) GetID

func (m *Battery2) GetID() uint32

GetID gets the ID of the Message

func (*Battery2) GetMessageName

func (m *Battery2) GetMessageName() string

GetMessageName gets the name of the Message

func (*Battery2) GetVersion

func (m *Battery2) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*Battery2) HasExtensionFields

func (m *Battery2) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*Battery2) Read

func (m *Battery2) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*Battery2) String

func (m *Battery2) String() string

func (*Battery2) Write

func (m *Battery2) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type CameraFeedback

type CameraFeedback struct {
	/*TimeUsec Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB). */
	TimeUsec uint64
	/*Lat Latitude. */
	Lat int32
	/*Lng Longitude. */
	Lng int32
	/*AltMsl Altitude (MSL). */
	AltMsl float32
	/*AltRel Altitude (Relative to HOME location). */
	AltRel float32
	/*Roll Camera Roll angle (earth frame, +-180). */
	Roll float32
	/*Pitch Camera Pitch angle (earth frame, +-180). */
	Pitch float32
	/*Yaw Camera Yaw (earth frame, 0-360, true). */
	Yaw float32
	/*FocLen Focal Length. */
	FocLen float32
	/*ImgIDx Image index. */
	ImgIDx uint16
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*CamIDx Camera ID. */
	CamIDx uint8
	/*Flags Feedback flags. */
	Flags uint8
	/*CompletedCaptures Completed image captures. */
	CompletedCaptures uint16
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

CameraFeedback Camera Capture Feedback.

func (*CameraFeedback) GetDialect

func (m *CameraFeedback) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*CameraFeedback) GetID

func (m *CameraFeedback) GetID() uint32

GetID gets the ID of the Message

func (*CameraFeedback) GetMessageName

func (m *CameraFeedback) GetMessageName() string

GetMessageName gets the name of the Message

func (*CameraFeedback) GetVersion

func (m *CameraFeedback) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*CameraFeedback) HasExtensionFields

func (m *CameraFeedback) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*CameraFeedback) Read

func (m *CameraFeedback) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*CameraFeedback) String

func (m *CameraFeedback) String() string

func (*CameraFeedback) Write

func (m *CameraFeedback) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type CameraStatus

type CameraStatus struct {
	/*TimeUsec Image timestamp (since UNIX epoch, according to camera clock). */
	TimeUsec uint64
	/*P1 Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). */
	P1 float32
	/*P2 Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). */
	P2 float32
	/*P3 Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). */
	P3 float32
	/*P4 Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). */
	P4 float32
	/*ImgIDx Image index. */
	ImgIDx uint16
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*CamIDx Camera ID. */
	CamIDx uint8
	/*EventID Event type. */
	EventID uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

CameraStatus Camera Event.

func (*CameraStatus) GetDialect

func (m *CameraStatus) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*CameraStatus) GetID

func (m *CameraStatus) GetID() uint32

GetID gets the ID of the Message

func (*CameraStatus) GetMessageName

func (m *CameraStatus) GetMessageName() string

GetMessageName gets the name of the Message

func (*CameraStatus) GetVersion

func (m *CameraStatus) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*CameraStatus) HasExtensionFields

func (m *CameraStatus) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*CameraStatus) Read

func (m *CameraStatus) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*CameraStatus) String

func (m *CameraStatus) String() string

func (*CameraStatus) Write

func (m *CameraStatus) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type CompassmotStatus

type CompassmotStatus struct {
	/*Current Current. */
	Current float32
	/*Compensationx Motor Compensation X. */
	Compensationx float32
	/*Compensationy Motor Compensation Y. */
	Compensationy float32
	/*Compensationz Motor Compensation Z. */
	Compensationz float32
	/*Throttle Throttle. */
	Throttle uint16
	/*Interference Interference. */
	Interference uint16
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

CompassmotStatus Status of compassmot calibration.

func (*CompassmotStatus) GetDialect

func (m *CompassmotStatus) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*CompassmotStatus) GetID

func (m *CompassmotStatus) GetID() uint32

GetID gets the ID of the Message

func (*CompassmotStatus) GetMessageName

func (m *CompassmotStatus) GetMessageName() string

GetMessageName gets the name of the Message

func (*CompassmotStatus) GetVersion

func (m *CompassmotStatus) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*CompassmotStatus) HasExtensionFields

func (m *CompassmotStatus) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*CompassmotStatus) Read

func (m *CompassmotStatus) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*CompassmotStatus) String

func (m *CompassmotStatus) String() string

func (*CompassmotStatus) Write

func (m *CompassmotStatus) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type Data16

type Data16 struct {
	/*Type Data type. */
	Type uint8
	/*Len Data length. */
	Len uint8
	/*Data Raw data. */
	Data [16]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

Data16 Data packet, size 16.

func (*Data16) GetDialect

func (m *Data16) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*Data16) GetID

func (m *Data16) GetID() uint32

GetID gets the ID of the Message

func (*Data16) GetMessageName

func (m *Data16) GetMessageName() string

GetMessageName gets the name of the Message

func (*Data16) GetVersion

func (m *Data16) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*Data16) HasExtensionFields

func (m *Data16) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*Data16) Read

func (m *Data16) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*Data16) String

func (m *Data16) String() string

func (*Data16) Write

func (m *Data16) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type Data32

type Data32 struct {
	/*Type Data type. */
	Type uint8
	/*Len Data length. */
	Len uint8
	/*Data Raw data. */
	Data [32]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

Data32 Data packet, size 32.

func (*Data32) GetDialect

func (m *Data32) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*Data32) GetID

func (m *Data32) GetID() uint32

GetID gets the ID of the Message

func (*Data32) GetMessageName

func (m *Data32) GetMessageName() string

GetMessageName gets the name of the Message

func (*Data32) GetVersion

func (m *Data32) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*Data32) HasExtensionFields

func (m *Data32) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*Data32) Read

func (m *Data32) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*Data32) String

func (m *Data32) String() string

func (*Data32) Write

func (m *Data32) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type Data64

type Data64 struct {
	/*Type Data type. */
	Type uint8
	/*Len Data length. */
	Len uint8
	/*Data Raw data. */
	Data [64]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

Data64 Data packet, size 64.

func (*Data64) GetDialect

func (m *Data64) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*Data64) GetID

func (m *Data64) GetID() uint32

GetID gets the ID of the Message

func (*Data64) GetMessageName

func (m *Data64) GetMessageName() string

GetMessageName gets the name of the Message

func (*Data64) GetVersion

func (m *Data64) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*Data64) HasExtensionFields

func (m *Data64) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*Data64) Read

func (m *Data64) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*Data64) String

func (m *Data64) String() string

func (*Data64) Write

func (m *Data64) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type Data96

type Data96 struct {
	/*Type Data type. */
	Type uint8
	/*Len Data length. */
	Len uint8
	/*Data Raw data. */
	Data [96]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

Data96 Data packet, size 96.

func (*Data96) GetDialect

func (m *Data96) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*Data96) GetID

func (m *Data96) GetID() uint32

GetID gets the ID of the Message

func (*Data96) GetMessageName

func (m *Data96) GetMessageName() string

GetMessageName gets the name of the Message

func (*Data96) GetVersion

func (m *Data96) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*Data96) HasExtensionFields

func (m *Data96) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*Data96) Read

func (m *Data96) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*Data96) String

func (m *Data96) String() string

func (*Data96) Write

func (m *Data96) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type Deepstall

type Deepstall struct {
	/*LandingLat Landing latitude. */
	LandingLat int32
	/*LandingLon Landing longitude. */
	LandingLon int32
	/*PathLat Final heading start point, latitude. */
	PathLat int32
	/*PathLon Final heading start point, longitude. */
	PathLon int32
	/*ARCEntryLat Arc entry point, latitude. */
	ARCEntryLat int32
	/*ARCEntryLon Arc entry point, longitude. */
	ARCEntryLon int32
	/*Altitude Altitude. */
	Altitude float32
	/*ExpectedTravelDistance Distance the aircraft expects to travel during the deepstall. */
	ExpectedTravelDistance float32
	/*CrossTrackError Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND). */
	CrossTrackError float32
	/*Stage Deepstall stage. */
	Stage uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

Deepstall Deepstall path planning.

func (*Deepstall) GetDialect

func (m *Deepstall) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*Deepstall) GetID

func (m *Deepstall) GetID() uint32

GetID gets the ID of the Message

func (*Deepstall) GetMessageName

func (m *Deepstall) GetMessageName() string

GetMessageName gets the name of the Message

func (*Deepstall) GetVersion

func (m *Deepstall) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*Deepstall) HasExtensionFields

func (m *Deepstall) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*Deepstall) Read

func (m *Deepstall) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*Deepstall) String

func (m *Deepstall) String() string

func (*Deepstall) Write

func (m *Deepstall) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type DeviceOpRead

type DeviceOpRead struct {
	/*RequestID Request ID - copied to reply. */
	RequestID uint32
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*Bustype The bus type. */
	Bustype uint8
	/*Bus Bus number. */
	Bus uint8
	/*Address Bus address. */
	Address uint8
	/*Busname Name of device on bus (for SPI). */
	Busname [40]byte
	/*Regstart First register to read. */
	Regstart uint8
	/*Count Count of registers to read. */
	Count uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

DeviceOpRead Read registers for a device.

func (*DeviceOpRead) GetBusname

func (m *DeviceOpRead) GetBusname() string

GetBusname decodes the null-terminated string in the Busname

func (*DeviceOpRead) GetDialect

func (m *DeviceOpRead) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*DeviceOpRead) GetID

func (m *DeviceOpRead) GetID() uint32

GetID gets the ID of the Message

func (*DeviceOpRead) GetMessageName

func (m *DeviceOpRead) GetMessageName() string

GetMessageName gets the name of the Message

func (*DeviceOpRead) GetVersion

func (m *DeviceOpRead) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*DeviceOpRead) HasExtensionFields

func (m *DeviceOpRead) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*DeviceOpRead) Read

func (m *DeviceOpRead) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*DeviceOpRead) SetBusname

func (m *DeviceOpRead) SetBusname(input string) (err error)

SetBusname encodes the input string to the Busname array

func (*DeviceOpRead) String

func (m *DeviceOpRead) String() string

func (*DeviceOpRead) Write

func (m *DeviceOpRead) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type DeviceOpReadReply

type DeviceOpReadReply struct {
	/*RequestID Request ID - copied from request. */
	RequestID uint32
	/*Result 0 for success, anything else is failure code. */
	Result uint8
	/*Regstart Starting register. */
	Regstart uint8
	/*Count Count of bytes read. */
	Count uint8
	/*Data Reply data. */
	Data [128]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

DeviceOpReadReply Read registers reply.

func (*DeviceOpReadReply) GetDialect

func (m *DeviceOpReadReply) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*DeviceOpReadReply) GetID

func (m *DeviceOpReadReply) GetID() uint32

GetID gets the ID of the Message

func (*DeviceOpReadReply) GetMessageName

func (m *DeviceOpReadReply) GetMessageName() string

GetMessageName gets the name of the Message

func (*DeviceOpReadReply) GetVersion

func (m *DeviceOpReadReply) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*DeviceOpReadReply) HasExtensionFields

func (m *DeviceOpReadReply) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*DeviceOpReadReply) Read

func (m *DeviceOpReadReply) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*DeviceOpReadReply) String

func (m *DeviceOpReadReply) String() string

func (*DeviceOpReadReply) Write

func (m *DeviceOpReadReply) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type DeviceOpWrite

type DeviceOpWrite struct {
	/*RequestID Request ID - copied to reply. */
	RequestID uint32
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*Bustype The bus type. */
	Bustype uint8
	/*Bus Bus number. */
	Bus uint8
	/*Address Bus address. */
	Address uint8
	/*Busname Name of device on bus (for SPI). */
	Busname [40]byte
	/*Regstart First register to write. */
	Regstart uint8
	/*Count Count of registers to write. */
	Count uint8
	/*Data Write data. */
	Data [128]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

DeviceOpWrite Write registers for a device.

func (*DeviceOpWrite) GetBusname

func (m *DeviceOpWrite) GetBusname() string

GetBusname decodes the null-terminated string in the Busname

func (*DeviceOpWrite) GetDialect

func (m *DeviceOpWrite) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*DeviceOpWrite) GetID

func (m *DeviceOpWrite) GetID() uint32

GetID gets the ID of the Message

func (*DeviceOpWrite) GetMessageName

func (m *DeviceOpWrite) GetMessageName() string

GetMessageName gets the name of the Message

func (*DeviceOpWrite) GetVersion

func (m *DeviceOpWrite) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*DeviceOpWrite) HasExtensionFields

func (m *DeviceOpWrite) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*DeviceOpWrite) Read

func (m *DeviceOpWrite) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*DeviceOpWrite) SetBusname

func (m *DeviceOpWrite) SetBusname(input string) (err error)

SetBusname encodes the input string to the Busname array

func (*DeviceOpWrite) String

func (m *DeviceOpWrite) String() string

func (*DeviceOpWrite) Write

func (m *DeviceOpWrite) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type DeviceOpWriteReply

type DeviceOpWriteReply struct {
	/*RequestID Request ID - copied from request. */
	RequestID uint32
	/*Result 0 for success, anything else is failure code. */
	Result uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

DeviceOpWriteReply Write registers reply.

func (*DeviceOpWriteReply) GetDialect

func (m *DeviceOpWriteReply) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*DeviceOpWriteReply) GetID

func (m *DeviceOpWriteReply) GetID() uint32

GetID gets the ID of the Message

func (*DeviceOpWriteReply) GetMessageName

func (m *DeviceOpWriteReply) GetMessageName() string

GetMessageName gets the name of the Message

func (*DeviceOpWriteReply) GetVersion

func (m *DeviceOpWriteReply) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*DeviceOpWriteReply) HasExtensionFields

func (m *DeviceOpWriteReply) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*DeviceOpWriteReply) Read

func (m *DeviceOpWriteReply) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*DeviceOpWriteReply) String

func (m *DeviceOpWriteReply) String() string

func (*DeviceOpWriteReply) Write

func (m *DeviceOpWriteReply) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type Dialect

type Dialect struct{}

Dialect represents a collection of MAVLink messages

func (Dialect) GetMessage

func (d Dialect) GetMessage(frame mavlink2.Frame) (message mavlink2.Message, err error)

GetMessage extracts and parses the message contained in the Frame

func (Dialect) GetMeta

func (d Dialect) GetMeta(messageID uint32) (meta mavlink2.MessageMeta, err error)

GetMeta retrieves the metadata for the message. If no metadata is found, ErrUnknownMessage is returned

func (Dialect) GetName

func (d Dialect) GetName() string

GetName gets the name of the Dialect

type DigicamConfigure

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

DigicamConfigure Configure on-board Camera Control System.

func (*DigicamConfigure) GetDialect

func (m *DigicamConfigure) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*DigicamConfigure) GetID

func (m *DigicamConfigure) GetID() uint32

GetID gets the ID of the Message

func (*DigicamConfigure) GetMessageName

func (m *DigicamConfigure) GetMessageName() string

GetMessageName gets the name of the Message

func (*DigicamConfigure) GetVersion

func (m *DigicamConfigure) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*DigicamConfigure) HasExtensionFields

func (m *DigicamConfigure) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*DigicamConfigure) Read

func (m *DigicamConfigure) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*DigicamConfigure) String

func (m *DigicamConfigure) String() string

func (*DigicamConfigure) Write

func (m *DigicamConfigure) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type DigicamControl

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

DigicamControl Control on-board Camera Control System to take shots.

func (*DigicamControl) GetDialect

func (m *DigicamControl) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*DigicamControl) GetID

func (m *DigicamControl) GetID() uint32

GetID gets the ID of the Message

func (*DigicamControl) GetMessageName

func (m *DigicamControl) GetMessageName() string

GetMessageName gets the name of the Message

func (*DigicamControl) GetVersion

func (m *DigicamControl) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*DigicamControl) HasExtensionFields

func (m *DigicamControl) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*DigicamControl) Read

func (m *DigicamControl) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*DigicamControl) String

func (m *DigicamControl) String() string

func (*DigicamControl) Write

func (m *DigicamControl) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type EKFStatusReport

type EKFStatusReport struct {
	/*VelocityVariance Velocity variance. */
	VelocityVariance float32
	/*PosHorizVariance Horizontal Position variance. */
	PosHorizVariance float32
	/*PosVertVariance Vertical Position variance. */
	PosVertVariance float32
	/*CompassVariance Compass variance. */
	CompassVariance float32
	/*TerrainAltVariance Terrain Altitude variance. */
	TerrainAltVariance float32
	/*Flags Flags. */
	Flags uint16
	/*AirspeedVariance Airspeed variance. */
	AirspeedVariance float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

EKFStatusReport EKF Status message including flags and variances.

func (*EKFStatusReport) GetDialect

func (m *EKFStatusReport) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*EKFStatusReport) GetID

func (m *EKFStatusReport) GetID() uint32

GetID gets the ID of the Message

func (*EKFStatusReport) GetMessageName

func (m *EKFStatusReport) GetMessageName() string

GetMessageName gets the name of the Message

func (*EKFStatusReport) GetVersion

func (m *EKFStatusReport) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*EKFStatusReport) HasExtensionFields

func (m *EKFStatusReport) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*EKFStatusReport) Read

func (m *EKFStatusReport) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*EKFStatusReport) String

func (m *EKFStatusReport) String() string

func (*EKFStatusReport) Write

func (m *EKFStatusReport) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type EfiStatus

type EfiStatus struct {
	/*EcuIndex ECU Index */
	EcuIndex float32
	/*Rpm RPM */
	Rpm float32
	/*FuelConsumed Fuel Consumed (grams) */
	FuelConsumed float32
	/*FuelFlow Fuel Flow Rate (g/min) */
	FuelFlow float32
	/*EngineLoad Engine Load (%) */
	EngineLoad float32
	/*ThrottlePosition Throttle Position (%) */
	ThrottlePosition float32
	/*SparkDwellTime Spark Dwell Time (ms) */
	SparkDwellTime float32
	/*BarometricPressure Barometric Pressure (kPa) */
	BarometricPressure float32
	/*IntakeManifoldPressure Intake Manifold Pressure (kPa)( */
	IntakeManifoldPressure float32
	/*IntakeManifoldTemperature Intake Manifold Temperature (degC) */
	IntakeManifoldTemperature float32
	/*CylinderHeadTemperature cylinder_head_temperature (degC) */
	CylinderHeadTemperature float32
	/*IgnitionTiming Ignition timing for cylinder i (Crank Angle degrees) */
	IgnitionTiming float32
	/*InjectionTime Injection time for injector i (ms) */
	InjectionTime float32
	/*Health EFI Health status */
	Health uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

EfiStatus EFI Status Output

func (*EfiStatus) GetDialect

func (m *EfiStatus) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*EfiStatus) GetID

func (m *EfiStatus) GetID() uint32

GetID gets the ID of the Message

func (*EfiStatus) GetMessageName

func (m *EfiStatus) GetMessageName() string

GetMessageName gets the name of the Message

func (*EfiStatus) GetVersion

func (m *EfiStatus) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*EfiStatus) HasExtensionFields

func (m *EfiStatus) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*EfiStatus) Read

func (m *EfiStatus) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*EfiStatus) String

func (m *EfiStatus) String() string

func (*EfiStatus) Write

func (m *EfiStatus) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type EscTelemetry1To4

type EscTelemetry1To4 struct {
	/*Voltage Voltage. */
	Voltage [4]uint16
	/*Current Current. */
	Current [4]uint16
	/*Totalcurrent Total current. */
	Totalcurrent [4]uint16
	/*Rpm RPM (eRPM). */
	Rpm [4]uint16
	/*Count count of telemetry packets received (wraps at 65535). */
	Count [4]uint16
	/*Temperature Temperature. */
	Temperature [4]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

EscTelemetry1To4 ESC Telemetry Data for ESCs 1 to 4, matching data sent by BLHeli ESCs.

func (*EscTelemetry1To4) GetDialect

func (m *EscTelemetry1To4) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*EscTelemetry1To4) GetID

func (m *EscTelemetry1To4) GetID() uint32

GetID gets the ID of the Message

func (*EscTelemetry1To4) GetMessageName

func (m *EscTelemetry1To4) GetMessageName() string

GetMessageName gets the name of the Message

func (*EscTelemetry1To4) GetVersion

func (m *EscTelemetry1To4) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*EscTelemetry1To4) HasExtensionFields

func (m *EscTelemetry1To4) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*EscTelemetry1To4) Read

func (m *EscTelemetry1To4) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*EscTelemetry1To4) String

func (m *EscTelemetry1To4) String() string

func (*EscTelemetry1To4) Write

func (m *EscTelemetry1To4) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type EscTelemetry5To8

type EscTelemetry5To8 struct {
	/*Voltage Voltage. */
	Voltage [4]uint16
	/*Current Current. */
	Current [4]uint16
	/*Totalcurrent Total current. */
	Totalcurrent [4]uint16
	/*Rpm RPM (eRPM). */
	Rpm [4]uint16
	/*Count count of telemetry packets received (wraps at 65535). */
	Count [4]uint16
	/*Temperature Temperature. */
	Temperature [4]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

EscTelemetry5To8 ESC Telemetry Data for ESCs 5 to 8, matching data sent by BLHeli ESCs.

func (*EscTelemetry5To8) GetDialect

func (m *EscTelemetry5To8) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*EscTelemetry5To8) GetID

func (m *EscTelemetry5To8) GetID() uint32

GetID gets the ID of the Message

func (*EscTelemetry5To8) GetMessageName

func (m *EscTelemetry5To8) GetMessageName() string

GetMessageName gets the name of the Message

func (*EscTelemetry5To8) GetVersion

func (m *EscTelemetry5To8) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*EscTelemetry5To8) HasExtensionFields

func (m *EscTelemetry5To8) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*EscTelemetry5To8) Read

func (m *EscTelemetry5To8) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*EscTelemetry5To8) String

func (m *EscTelemetry5To8) String() string

func (*EscTelemetry5To8) Write

func (m *EscTelemetry5To8) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type EscTelemetry9To12

type EscTelemetry9To12 struct {
	/*Voltage Voltage. */
	Voltage [4]uint16
	/*Current Current. */
	Current [4]uint16
	/*Totalcurrent Total current. */
	Totalcurrent [4]uint16
	/*Rpm RPM (eRPM). */
	Rpm [4]uint16
	/*Count count of telemetry packets received (wraps at 65535). */
	Count [4]uint16
	/*Temperature Temperature. */
	Temperature [4]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

EscTelemetry9To12 ESC Telemetry Data for ESCs 9 to 12, matching data sent by BLHeli ESCs.

func (*EscTelemetry9To12) GetDialect

func (m *EscTelemetry9To12) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*EscTelemetry9To12) GetID

func (m *EscTelemetry9To12) GetID() uint32

GetID gets the ID of the Message

func (*EscTelemetry9To12) GetMessageName

func (m *EscTelemetry9To12) GetMessageName() string

GetMessageName gets the name of the Message

func (*EscTelemetry9To12) GetVersion

func (m *EscTelemetry9To12) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*EscTelemetry9To12) HasExtensionFields

func (m *EscTelemetry9To12) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*EscTelemetry9To12) Read

func (m *EscTelemetry9To12) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*EscTelemetry9To12) String

func (m *EscTelemetry9To12) String() string

func (*EscTelemetry9To12) Write

func (m *EscTelemetry9To12) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type FenceFetchPoint

type FenceFetchPoint struct {
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*IDx Point index (first point is 1, 0 is for return point). */
	IDx uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

FenceFetchPoint Request a current fence point from MAV.

func (*FenceFetchPoint) GetDialect

func (m *FenceFetchPoint) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*FenceFetchPoint) GetID

func (m *FenceFetchPoint) GetID() uint32

GetID gets the ID of the Message

func (*FenceFetchPoint) GetMessageName

func (m *FenceFetchPoint) GetMessageName() string

GetMessageName gets the name of the Message

func (*FenceFetchPoint) GetVersion

func (m *FenceFetchPoint) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*FenceFetchPoint) HasExtensionFields

func (m *FenceFetchPoint) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*FenceFetchPoint) Read

func (m *FenceFetchPoint) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*FenceFetchPoint) String

func (m *FenceFetchPoint) String() string

func (*FenceFetchPoint) Write

func (m *FenceFetchPoint) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type FencePoint

type FencePoint struct {
	/*Lat Latitude of point. */
	Lat float32
	/*Lng Longitude of point. */
	Lng float32
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*IDx Point index (first point is 1, 0 is for return point). */
	IDx uint8
	/*Count Total number of points (for sanity checking). */
	Count uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

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

func (*FencePoint) GetDialect

func (m *FencePoint) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*FencePoint) GetID

func (m *FencePoint) GetID() uint32

GetID gets the ID of the Message

func (*FencePoint) GetMessageName

func (m *FencePoint) GetMessageName() string

GetMessageName gets the name of the Message

func (*FencePoint) GetVersion

func (m *FencePoint) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*FencePoint) HasExtensionFields

func (m *FencePoint) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*FencePoint) Read

func (m *FencePoint) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*FencePoint) String

func (m *FencePoint) String() string

func (*FencePoint) Write

func (m *FencePoint) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type FenceStatus

type FenceStatus struct {
	/*BreachTime Time (since boot) of last breach. */
	BreachTime uint32
	/*BreachCount Number of fence breaches. */
	BreachCount uint16
	/*BreachStatus Breach status (0 if currently inside fence, 1 if outside). */
	BreachStatus uint8
	/*BreachType Last breach type. */
	BreachType uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

FenceStatus Status of geo-fencing. Sent in extended status stream when fencing enabled.

func (*FenceStatus) GetDialect

func (m *FenceStatus) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*FenceStatus) GetID

func (m *FenceStatus) GetID() uint32

GetID gets the ID of the Message

func (*FenceStatus) GetMessageName

func (m *FenceStatus) GetMessageName() string

GetMessageName gets the name of the Message

func (*FenceStatus) GetVersion

func (m *FenceStatus) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*FenceStatus) HasExtensionFields

func (m *FenceStatus) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*FenceStatus) Read

func (m *FenceStatus) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*FenceStatus) String

func (m *FenceStatus) String() string

func (*FenceStatus) Write

func (m *FenceStatus) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type GimbalControl

type GimbalControl struct {
	/*DemandedRateX Demanded angular rate X. */
	DemandedRateX float32
	/*DemandedRateY Demanded angular rate Y. */
	DemandedRateY float32
	/*DemandedRateZ Demanded angular rate Z. */
	DemandedRateZ float32
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

GimbalControl Control message for rate gimbal.

func (*GimbalControl) GetDialect

func (m *GimbalControl) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*GimbalControl) GetID

func (m *GimbalControl) GetID() uint32

GetID gets the ID of the Message

func (*GimbalControl) GetMessageName

func (m *GimbalControl) GetMessageName() string

GetMessageName gets the name of the Message

func (*GimbalControl) GetVersion

func (m *GimbalControl) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*GimbalControl) HasExtensionFields

func (m *GimbalControl) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*GimbalControl) Read

func (m *GimbalControl) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*GimbalControl) String

func (m *GimbalControl) String() string

func (*GimbalControl) Write

func (m *GimbalControl) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type GimbalReport

type GimbalReport struct {
	/*DeltaTime Time since last update. */
	DeltaTime float32
	/*DeltaAngleX Delta angle X. */
	DeltaAngleX float32
	/*DeltaAngleY Delta angle Y. */
	DeltaAngleY float32
	/*DeltaAngleZ Delta angle X. */
	DeltaAngleZ float32
	/*DeltaVelocityX Delta velocity X. */
	DeltaVelocityX float32
	/*DeltaVelocityY Delta velocity Y. */
	DeltaVelocityY float32
	/*DeltaVelocityZ Delta velocity Z. */
	DeltaVelocityZ float32
	/*JointRoll Joint ROLL. */
	JointRoll float32
	/*JointEl Joint EL. */
	JointEl float32
	/*JointAz Joint AZ. */
	JointAz float32
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

GimbalReport 3 axis gimbal measurements.

func (*GimbalReport) GetDialect

func (m *GimbalReport) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*GimbalReport) GetID

func (m *GimbalReport) GetID() uint32

GetID gets the ID of the Message

func (*GimbalReport) GetMessageName

func (m *GimbalReport) GetMessageName() string

GetMessageName gets the name of the Message

func (*GimbalReport) GetVersion

func (m *GimbalReport) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*GimbalReport) HasExtensionFields

func (m *GimbalReport) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*GimbalReport) Read

func (m *GimbalReport) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*GimbalReport) String

func (m *GimbalReport) String() string

func (*GimbalReport) Write

func (m *GimbalReport) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type GimbalTorqueCmdReport

type GimbalTorqueCmdReport struct {
	/*RlTorqueCmd Roll Torque Command. */
	RlTorqueCmd int16
	/*ElTorqueCmd Elevation Torque Command. */
	ElTorqueCmd int16
	/*AzTorqueCmd Azimuth Torque Command. */
	AzTorqueCmd int16
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

GimbalTorqueCmdReport 100 Hz gimbal torque command telemetry.

func (*GimbalTorqueCmdReport) GetDialect

func (m *GimbalTorqueCmdReport) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*GimbalTorqueCmdReport) GetID

func (m *GimbalTorqueCmdReport) GetID() uint32

GetID gets the ID of the Message

func (*GimbalTorqueCmdReport) GetMessageName

func (m *GimbalTorqueCmdReport) GetMessageName() string

GetMessageName gets the name of the Message

func (*GimbalTorqueCmdReport) GetVersion

func (m *GimbalTorqueCmdReport) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*GimbalTorqueCmdReport) HasExtensionFields

func (m *GimbalTorqueCmdReport) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*GimbalTorqueCmdReport) Read

func (m *GimbalTorqueCmdReport) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*GimbalTorqueCmdReport) String

func (m *GimbalTorqueCmdReport) String() string

func (*GimbalTorqueCmdReport) Write

func (m *GimbalTorqueCmdReport) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type GoproGetRequest

type GoproGetRequest struct {
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*CmdID Command ID. */
	CmdID uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

GoproGetRequest Request a GOPRO_COMMAND response from the GoPro.

func (*GoproGetRequest) GetDialect

func (m *GoproGetRequest) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*GoproGetRequest) GetID

func (m *GoproGetRequest) GetID() uint32

GetID gets the ID of the Message

func (*GoproGetRequest) GetMessageName

func (m *GoproGetRequest) GetMessageName() string

GetMessageName gets the name of the Message

func (*GoproGetRequest) GetVersion

func (m *GoproGetRequest) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*GoproGetRequest) HasExtensionFields

func (m *GoproGetRequest) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*GoproGetRequest) Read

func (m *GoproGetRequest) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*GoproGetRequest) String

func (m *GoproGetRequest) String() string

func (*GoproGetRequest) Write

func (m *GoproGetRequest) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type GoproGetResponse

type GoproGetResponse struct {
	/*CmdID Command ID. */
	CmdID uint8
	/*Status Status. */
	Status uint8
	/*Value Value. */
	Value [4]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

GoproGetResponse Response from a GOPRO_COMMAND get request.

func (*GoproGetResponse) GetDialect

func (m *GoproGetResponse) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*GoproGetResponse) GetID

func (m *GoproGetResponse) GetID() uint32

GetID gets the ID of the Message

func (*GoproGetResponse) GetMessageName

func (m *GoproGetResponse) GetMessageName() string

GetMessageName gets the name of the Message

func (*GoproGetResponse) GetVersion

func (m *GoproGetResponse) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*GoproGetResponse) HasExtensionFields

func (m *GoproGetResponse) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*GoproGetResponse) Read

func (m *GoproGetResponse) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*GoproGetResponse) String

func (m *GoproGetResponse) String() string

func (*GoproGetResponse) Write

func (m *GoproGetResponse) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type GoproHeartbeat

type GoproHeartbeat struct {
	/*Status Status. */
	Status uint8
	/*CaptureMode Current capture mode. */
	CaptureMode uint8
	/*Flags Additional status bits. */
	Flags uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

GoproHeartbeat Heartbeat from a HeroBus attached GoPro.

func (*GoproHeartbeat) GetDialect

func (m *GoproHeartbeat) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*GoproHeartbeat) GetID

func (m *GoproHeartbeat) GetID() uint32

GetID gets the ID of the Message

func (*GoproHeartbeat) GetMessageName

func (m *GoproHeartbeat) GetMessageName() string

GetMessageName gets the name of the Message

func (*GoproHeartbeat) GetVersion

func (m *GoproHeartbeat) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*GoproHeartbeat) HasExtensionFields

func (m *GoproHeartbeat) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*GoproHeartbeat) Read

func (m *GoproHeartbeat) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*GoproHeartbeat) String

func (m *GoproHeartbeat) String() string

func (*GoproHeartbeat) Write

func (m *GoproHeartbeat) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type GoproSetRequest

type GoproSetRequest struct {
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*CmdID Command ID. */
	CmdID uint8
	/*Value Value. */
	Value [4]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

GoproSetRequest Request to set a GOPRO_COMMAND with a desired.

func (*GoproSetRequest) GetDialect

func (m *GoproSetRequest) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*GoproSetRequest) GetID

func (m *GoproSetRequest) GetID() uint32

GetID gets the ID of the Message

func (*GoproSetRequest) GetMessageName

func (m *GoproSetRequest) GetMessageName() string

GetMessageName gets the name of the Message

func (*GoproSetRequest) GetVersion

func (m *GoproSetRequest) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*GoproSetRequest) HasExtensionFields

func (m *GoproSetRequest) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*GoproSetRequest) Read

func (m *GoproSetRequest) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*GoproSetRequest) String

func (m *GoproSetRequest) String() string

func (*GoproSetRequest) Write

func (m *GoproSetRequest) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type GoproSetResponse

type GoproSetResponse struct {
	/*CmdID Command ID. */
	CmdID uint8
	/*Status Status. */
	Status uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

GoproSetResponse Response from a GOPRO_COMMAND set request.

func (*GoproSetResponse) GetDialect

func (m *GoproSetResponse) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*GoproSetResponse) GetID

func (m *GoproSetResponse) GetID() uint32

GetID gets the ID of the Message

func (*GoproSetResponse) GetMessageName

func (m *GoproSetResponse) GetMessageName() string

GetMessageName gets the name of the Message

func (*GoproSetResponse) GetVersion

func (m *GoproSetResponse) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*GoproSetResponse) HasExtensionFields

func (m *GoproSetResponse) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*GoproSetResponse) Read

func (m *GoproSetResponse) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*GoproSetResponse) String

func (m *GoproSetResponse) String() string

func (*GoproSetResponse) Write

func (m *GoproSetResponse) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type HWstatus

type HWstatus struct {
	/*Vcc Board voltage. */
	Vcc uint16
	/*I2Cerr I2C error count. */
	I2Cerr uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

HWstatus Status of key hardware.

func (*HWstatus) GetDialect

func (m *HWstatus) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*HWstatus) GetID

func (m *HWstatus) GetID() uint32

GetID gets the ID of the Message

func (*HWstatus) GetMessageName

func (m *HWstatus) GetMessageName() string

GetMessageName gets the name of the Message

func (*HWstatus) GetVersion

func (m *HWstatus) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*HWstatus) HasExtensionFields

func (m *HWstatus) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*HWstatus) Read

func (m *HWstatus) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*HWstatus) String

func (m *HWstatus) String() string

func (*HWstatus) Write

func (m *HWstatus) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type LedControl

type LedControl struct {
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*Instance Instance (LED instance to control or 255 for all LEDs). */
	Instance uint8
	/*Pattern Pattern (see LED_PATTERN_ENUM). */
	Pattern uint8
	/*CustomLen Custom Byte Length. */
	CustomLen uint8
	/*CustomBytes Custom Bytes. */
	CustomBytes [24]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

LedControl Control vehicle LEDs.

func (*LedControl) GetDialect

func (m *LedControl) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*LedControl) GetID

func (m *LedControl) GetID() uint32

GetID gets the ID of the Message

func (*LedControl) GetMessageName

func (m *LedControl) GetMessageName() string

GetMessageName gets the name of the Message

func (*LedControl) GetVersion

func (m *LedControl) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*LedControl) HasExtensionFields

func (m *LedControl) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*LedControl) Read

func (m *LedControl) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*LedControl) String

func (m *LedControl) String() string

func (*LedControl) Write

func (m *LedControl) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type LimitsStatus

type LimitsStatus struct {
	/*LastTrigger Time (since boot) of last breach. */
	LastTrigger uint32
	/*LastAction Time (since boot) of last recovery action. */
	LastAction uint32
	/*LastRecovery Time (since boot) of last successful recovery. */
	LastRecovery uint32
	/*LastClear Time (since boot) of last all-clear. */
	LastClear uint32
	/*BreachCount Number of fence breaches. */
	BreachCount uint16
	/*LimitsState State of AP_Limits. */
	LimitsState uint8
	/*ModsEnabled AP_Limit_Module bitfield of enabled modules. */
	ModsEnabled uint8
	/*ModsRequired AP_Limit_Module bitfield of required modules. */
	ModsRequired uint8
	/*ModsTriggered AP_Limit_Module bitfield of triggered modules. */
	ModsTriggered uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

LimitsStatus Status of AP_Limits. Sent in extended status stream when AP_Limits is enabled.

func (*LimitsStatus) GetDialect

func (m *LimitsStatus) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*LimitsStatus) GetID

func (m *LimitsStatus) GetID() uint32

GetID gets the ID of the Message

func (*LimitsStatus) GetMessageName

func (m *LimitsStatus) GetMessageName() string

GetMessageName gets the name of the Message

func (*LimitsStatus) GetVersion

func (m *LimitsStatus) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*LimitsStatus) HasExtensionFields

func (m *LimitsStatus) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*LimitsStatus) Read

func (m *LimitsStatus) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*LimitsStatus) String

func (m *LimitsStatus) String() string

func (*LimitsStatus) Write

func (m *LimitsStatus) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type MagCalProgress

type MagCalProgress struct {
	/*DirectionX Body frame direction vector for display. */
	DirectionX float32
	/*DirectionY Body frame direction vector for display. */
	DirectionY float32
	/*DirectionZ Body frame direction vector for display. */
	DirectionZ float32
	/*CompassID Compass being calibrated. */
	CompassID uint8
	/*CalMask Bitmask of compasses being calibrated. */
	CalMask uint8
	/*CalStatus Calibration Status. */
	CalStatus uint8
	/*Attempt Attempt number. */
	Attempt uint8
	/*CompletionPct Completion percentage. */
	CompletionPct uint8
	/*CompletionMask Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid). */
	CompletionMask [10]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

MagCalProgress Reports progress of compass calibration.

func (*MagCalProgress) GetDialect

func (m *MagCalProgress) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*MagCalProgress) GetID

func (m *MagCalProgress) GetID() uint32

GetID gets the ID of the Message

func (*MagCalProgress) GetMessageName

func (m *MagCalProgress) GetMessageName() string

GetMessageName gets the name of the Message

func (*MagCalProgress) GetVersion

func (m *MagCalProgress) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*MagCalProgress) HasExtensionFields

func (m *MagCalProgress) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*MagCalProgress) Read

func (m *MagCalProgress) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*MagCalProgress) String

func (m *MagCalProgress) String() string

func (*MagCalProgress) Write

func (m *MagCalProgress) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type MagCalReport

type MagCalReport struct {
	/*Fitness RMS milligauss residuals. */
	Fitness float32
	/*OfsX X offset. */
	OfsX float32
	/*OfsY Y offset. */
	OfsY float32
	/*OfsZ Z offset. */
	OfsZ float32
	/*DiagX X diagonal (matrix 11). */
	DiagX float32
	/*DiagY Y diagonal (matrix 22). */
	DiagY float32
	/*DiagZ Z diagonal (matrix 33). */
	DiagZ float32
	/*OffdiagX X off-diagonal (matrix 12 and 21). */
	OffdiagX float32
	/*OffdiagY Y off-diagonal (matrix 13 and 31). */
	OffdiagY float32
	/*OffdiagZ Z off-diagonal (matrix 32 and 23). */
	OffdiagZ float32
	/*CompassID Compass being calibrated. */
	CompassID uint8
	/*CalMask Bitmask of compasses being calibrated. */
	CalMask uint8
	/*CalStatus Calibration Status. */
	CalStatus uint8
	/*Autosaved 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters. */
	Autosaved uint8
	/*OrientationConfIDence Confidence in orientation (higher is better). */
	OrientationConfIDence float32
	/*OldOrientation orientation before calibration. */
	OldOrientation uint8
	/*NewOrientation orientation after calibration. */
	NewOrientation uint8
	/*ScaleFactor field radius correction factor */
	ScaleFactor float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

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

func (*MagCalReport) GetDialect

func (m *MagCalReport) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*MagCalReport) GetID

func (m *MagCalReport) GetID() uint32

GetID gets the ID of the Message

func (*MagCalReport) GetMessageName

func (m *MagCalReport) GetMessageName() string

GetMessageName gets the name of the Message

func (*MagCalReport) GetVersion

func (m *MagCalReport) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*MagCalReport) HasExtensionFields

func (m *MagCalReport) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*MagCalReport) Read

func (m *MagCalReport) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*MagCalReport) String

func (m *MagCalReport) String() string

func (*MagCalReport) Write

func (m *MagCalReport) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type MemInfo

type MemInfo struct {
	/*Brkval Heap top. */
	Brkval uint16
	/*Freemem Free memory. */
	Freemem uint16
	/*Freemem32 Free memory (32 bit). */
	Freemem32 uint32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

MemInfo State of APM memory.

func (*MemInfo) GetDialect

func (m *MemInfo) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*MemInfo) GetID

func (m *MemInfo) GetID() uint32

GetID gets the ID of the Message

func (*MemInfo) GetMessageName

func (m *MemInfo) GetMessageName() string

GetMessageName gets the name of the Message

func (*MemInfo) GetVersion

func (m *MemInfo) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*MemInfo) HasExtensionFields

func (m *MemInfo) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*MemInfo) Read

func (m *MemInfo) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*MemInfo) String

func (m *MemInfo) String() string

func (*MemInfo) Write

func (m *MemInfo) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type MountConfigure

type MountConfigure struct {
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*MountMode Mount operating mode. */
	MountMode uint8
	/*StabRoll (1 = yes, 0 = no). */
	StabRoll uint8
	/*StabPitch (1 = yes, 0 = no). */
	StabPitch uint8
	/*StabYaw (1 = yes, 0 = no). */
	StabYaw uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

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

func (*MountConfigure) GetDialect

func (m *MountConfigure) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*MountConfigure) GetID

func (m *MountConfigure) GetID() uint32

GetID gets the ID of the Message

func (*MountConfigure) GetMessageName

func (m *MountConfigure) GetMessageName() string

GetMessageName gets the name of the Message

func (*MountConfigure) GetVersion

func (m *MountConfigure) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*MountConfigure) HasExtensionFields

func (m *MountConfigure) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*MountConfigure) Read

func (m *MountConfigure) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*MountConfigure) String

func (m *MountConfigure) String() string

func (*MountConfigure) Write

func (m *MountConfigure) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type MountControl

type MountControl struct {
	/*InputA Pitch (centi-degrees) or lat (degE7), depending on mount mode. */
	InputA int32
	/*InputB Roll (centi-degrees) or lon (degE7) depending on mount mode. */
	InputB int32
	/*InputC Yaw (centi-degrees) or alt (cm) depending on mount mode. */
	InputC int32
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*SavePosition If "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING). */
	SavePosition uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

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

func (*MountControl) GetDialect

func (m *MountControl) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*MountControl) GetID

func (m *MountControl) GetID() uint32

GetID gets the ID of the Message

func (*MountControl) GetMessageName

func (m *MountControl) GetMessageName() string

GetMessageName gets the name of the Message

func (*MountControl) GetVersion

func (m *MountControl) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*MountControl) HasExtensionFields

func (m *MountControl) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*MountControl) Read

func (m *MountControl) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*MountControl) String

func (m *MountControl) String() string

func (*MountControl) Write

func (m *MountControl) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type MountStatus

type MountStatus struct {
	/*PointingA Pitch. */
	PointingA int32
	/*PointingB Roll. */
	PointingB int32
	/*PointingC Yaw. */
	PointingC int32
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

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

func (*MountStatus) GetDialect

func (m *MountStatus) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*MountStatus) GetID

func (m *MountStatus) GetID() uint32

GetID gets the ID of the Message

func (*MountStatus) GetMessageName

func (m *MountStatus) GetMessageName() string

GetMessageName gets the name of the Message

func (*MountStatus) GetVersion

func (m *MountStatus) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*MountStatus) HasExtensionFields

func (m *MountStatus) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*MountStatus) Read

func (m *MountStatus) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*MountStatus) String

func (m *MountStatus) String() string

func (*MountStatus) Write

func (m *MountStatus) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type PIDTuning

type PIDTuning struct {
	/*Desired Desired rate. */
	Desired float32
	/*Achieved Achieved rate. */
	Achieved float32
	/*Ff FF component. */
	Ff float32
	/*P P component. */
	P float32
	/*I I component. */
	I float32
	/*D D component. */
	D float32
	/*Axis Axis. */
	Axis uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

PIDTuning PID tuning information.

func (*PIDTuning) GetDialect

func (m *PIDTuning) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*PIDTuning) GetID

func (m *PIDTuning) GetID() uint32

GetID gets the ID of the Message

func (*PIDTuning) GetMessageName

func (m *PIDTuning) GetMessageName() string

GetMessageName gets the name of the Message

func (*PIDTuning) GetVersion

func (m *PIDTuning) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*PIDTuning) HasExtensionFields

func (m *PIDTuning) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*PIDTuning) Read

func (m *PIDTuning) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*PIDTuning) String

func (m *PIDTuning) String() string

func (*PIDTuning) Write

func (m *PIDTuning) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type Radio

type Radio struct {
	/*Rxerrors Receive errors. */
	Rxerrors uint16
	/*Fixed Count of error corrected packets. */
	Fixed uint16
	/*RSSI Local signal strength. */
	RSSI uint8
	/*RemRSSI Remote signal strength. */
	RemRSSI uint8
	/*Txbuf How full the tx buffer is. */
	Txbuf uint8
	/*Noise Background noise level. */
	Noise uint8
	/*Remnoise Remote background noise level. */
	Remnoise uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

Radio Status generated by radio.

func (*Radio) GetDialect

func (m *Radio) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*Radio) GetID

func (m *Radio) GetID() uint32

GetID gets the ID of the Message

func (*Radio) GetMessageName

func (m *Radio) GetMessageName() string

GetMessageName gets the name of the Message

func (*Radio) GetVersion

func (m *Radio) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*Radio) HasExtensionFields

func (m *Radio) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*Radio) Read

func (m *Radio) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*Radio) String

func (m *Radio) String() string

func (*Radio) Write

func (m *Radio) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type RallyFetchPoint

type RallyFetchPoint struct {
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*IDx Point index (first point is 0). */
	IDx uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

RallyFetchPoint 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) GetDialect

func (m *RallyFetchPoint) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*RallyFetchPoint) GetID

func (m *RallyFetchPoint) GetID() uint32

GetID gets the ID of the Message

func (*RallyFetchPoint) GetMessageName

func (m *RallyFetchPoint) GetMessageName() string

GetMessageName gets the name of the Message

func (*RallyFetchPoint) GetVersion

func (m *RallyFetchPoint) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*RallyFetchPoint) HasExtensionFields

func (m *RallyFetchPoint) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*RallyFetchPoint) Read

func (m *RallyFetchPoint) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*RallyFetchPoint) String

func (m *RallyFetchPoint) String() string

func (*RallyFetchPoint) Write

func (m *RallyFetchPoint) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type RallyPoint

type RallyPoint struct {
	/*Lat Latitude of point. */
	Lat int32
	/*Lng Longitude of point. */
	Lng int32
	/*Alt Transit / loiter altitude relative to home. */
	Alt int16
	/*BreakAlt Break altitude relative to home. */
	BreakAlt int16
	/*LandDir Heading to aim for when landing. */
	LandDir uint16
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*IDx Point index (first point is 0). */
	IDx uint8
	/*Count Total number of points (for sanity checking). */
	Count uint8
	/*Flags Configuration flags. */
	Flags uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

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

func (*RallyPoint) GetDialect

func (m *RallyPoint) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*RallyPoint) GetID

func (m *RallyPoint) GetID() uint32

GetID gets the ID of the Message

func (*RallyPoint) GetMessageName

func (m *RallyPoint) GetMessageName() string

GetMessageName gets the name of the Message

func (*RallyPoint) GetVersion

func (m *RallyPoint) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*RallyPoint) HasExtensionFields

func (m *RallyPoint) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*RallyPoint) Read

func (m *RallyPoint) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*RallyPoint) String

func (m *RallyPoint) String() string

func (*RallyPoint) Write

func (m *RallyPoint) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type Rangefinder

type Rangefinder struct {
	/*Distance Distance. */
	Distance float32
	/*Voltage Raw voltage if available, zero otherwise. */
	Voltage float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

Rangefinder Rangefinder reporting.

func (*Rangefinder) GetDialect

func (m *Rangefinder) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*Rangefinder) GetID

func (m *Rangefinder) GetID() uint32

GetID gets the ID of the Message

func (*Rangefinder) GetMessageName

func (m *Rangefinder) GetMessageName() string

GetMessageName gets the name of the Message

func (*Rangefinder) GetVersion

func (m *Rangefinder) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*Rangefinder) HasExtensionFields

func (m *Rangefinder) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*Rangefinder) Read

func (m *Rangefinder) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*Rangefinder) String

func (m *Rangefinder) String() string

func (*Rangefinder) Write

func (m *Rangefinder) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type RemoteLogBlockStatus

type RemoteLogBlockStatus struct {
	/*Seqno Log data block sequence number. */
	Seqno uint32
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*Status Log data block status. */
	Status uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

RemoteLogBlockStatus Send Status of each log block that autopilot board might have sent.

func (*RemoteLogBlockStatus) GetDialect

func (m *RemoteLogBlockStatus) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*RemoteLogBlockStatus) GetID

func (m *RemoteLogBlockStatus) GetID() uint32

GetID gets the ID of the Message

func (*RemoteLogBlockStatus) GetMessageName

func (m *RemoteLogBlockStatus) GetMessageName() string

GetMessageName gets the name of the Message

func (*RemoteLogBlockStatus) GetVersion

func (m *RemoteLogBlockStatus) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*RemoteLogBlockStatus) HasExtensionFields

func (m *RemoteLogBlockStatus) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*RemoteLogBlockStatus) Read

func (m *RemoteLogBlockStatus) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*RemoteLogBlockStatus) String

func (m *RemoteLogBlockStatus) String() string

func (*RemoteLogBlockStatus) Write

func (m *RemoteLogBlockStatus) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type RemoteLogDataBlock

type RemoteLogDataBlock struct {
	/*Seqno Log data block sequence number. */
	Seqno uint32
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*Data Log data block. */
	Data [200]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

RemoteLogDataBlock Send a block of log data to remote location.

func (*RemoteLogDataBlock) GetDialect

func (m *RemoteLogDataBlock) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*RemoteLogDataBlock) GetID

func (m *RemoteLogDataBlock) GetID() uint32

GetID gets the ID of the Message

func (*RemoteLogDataBlock) GetMessageName

func (m *RemoteLogDataBlock) GetMessageName() string

GetMessageName gets the name of the Message

func (*RemoteLogDataBlock) GetVersion

func (m *RemoteLogDataBlock) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*RemoteLogDataBlock) HasExtensionFields

func (m *RemoteLogDataBlock) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*RemoteLogDataBlock) Read

func (m *RemoteLogDataBlock) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*RemoteLogDataBlock) String

func (m *RemoteLogDataBlock) String() string

func (*RemoteLogDataBlock) Write

func (m *RemoteLogDataBlock) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type Rpm

type Rpm struct {
	/*Rpm1 RPM Sensor1. */
	Rpm1 float32
	/*Rpm2 RPM Sensor2. */
	Rpm2 float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

Rpm RPM sensor output.

func (*Rpm) GetDialect

func (m *Rpm) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*Rpm) GetID

func (m *Rpm) GetID() uint32

GetID gets the ID of the Message

func (*Rpm) GetMessageName

func (m *Rpm) GetMessageName() string

GetMessageName gets the name of the Message

func (*Rpm) GetVersion

func (m *Rpm) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*Rpm) HasExtensionFields

func (m *Rpm) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*Rpm) Read

func (m *Rpm) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*Rpm) String

func (m *Rpm) String() string

func (*Rpm) Write

func (m *Rpm) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type SensorOffsets

type SensorOffsets struct {
	/*MagDeclination Magnetic declination. */
	MagDeclination float32
	/*RawPress Raw pressure from barometer. */
	RawPress int32
	/*RawTemp Raw temperature from barometer. */
	RawTemp int32
	/*GyroCalX Gyro X calibration. */
	GyroCalX float32
	/*GyroCalY Gyro Y calibration. */
	GyroCalY float32
	/*GyroCalZ Gyro Z calibration. */
	GyroCalZ float32
	/*AccelCalX Accel X calibration. */
	AccelCalX float32
	/*AccelCalY Accel Y calibration. */
	AccelCalY float32
	/*AccelCalZ Accel Z calibration. */
	AccelCalZ float32
	/*MagOfsX Magnetometer X offset. */
	MagOfsX int16
	/*MagOfsY Magnetometer Y offset. */
	MagOfsY int16
	/*MagOfsZ Magnetometer Z offset. */
	MagOfsZ int16
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SensorOffsets Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process.

func (*SensorOffsets) GetDialect

func (m *SensorOffsets) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SensorOffsets) GetID

func (m *SensorOffsets) GetID() uint32

GetID gets the ID of the Message

func (*SensorOffsets) GetMessageName

func (m *SensorOffsets) GetMessageName() string

GetMessageName gets the name of the Message

func (*SensorOffsets) GetVersion

func (m *SensorOffsets) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SensorOffsets) HasExtensionFields

func (m *SensorOffsets) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*SensorOffsets) Read

func (m *SensorOffsets) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*SensorOffsets) String

func (m *SensorOffsets) String() string

func (*SensorOffsets) Write

func (m *SensorOffsets) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type SetMagOffsets

type SetMagOffsets struct {
	/*MagOfsX Magnetometer X offset. */
	MagOfsX int16
	/*MagOfsY Magnetometer Y offset. */
	MagOfsY int16
	/*MagOfsZ Magnetometer Z offset. */
	MagOfsZ int16
	/*TargetSystem System ID. */
	TargetSystem uint8
	/*TargetComponent Component ID. */
	TargetComponent uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SetMagOffsets Set the magnetometer offsets

func (*SetMagOffsets) GetDialect

func (m *SetMagOffsets) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SetMagOffsets) GetID

func (m *SetMagOffsets) GetID() uint32

GetID gets the ID of the Message

func (*SetMagOffsets) GetMessageName

func (m *SetMagOffsets) GetMessageName() string

GetMessageName gets the name of the Message

func (*SetMagOffsets) GetVersion

func (m *SetMagOffsets) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SetMagOffsets) HasExtensionFields

func (m *SetMagOffsets) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*SetMagOffsets) Read

func (m *SetMagOffsets) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*SetMagOffsets) String

func (m *SetMagOffsets) String() string

func (*SetMagOffsets) Write

func (m *SetMagOffsets) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type SimState

type SimState struct {
	/*Roll Roll angle. */
	Roll float32
	/*Pitch Pitch angle. */
	Pitch float32
	/*Yaw Yaw angle. */
	Yaw float32
	/*Xacc X acceleration. */
	Xacc float32
	/*Yacc Y acceleration. */
	Yacc float32
	/*Zacc Z acceleration. */
	Zacc float32
	/*Xgyro Angular speed around X axis. */
	Xgyro float32
	/*Ygyro Angular speed around Y axis. */
	Ygyro float32
	/*Zgyro Angular speed around Z axis. */
	Zgyro float32
	/*Lat Latitude. */
	Lat int32
	/*Lng Longitude. */
	Lng int32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SimState Status of simulation environment, if used.

func (*SimState) GetDialect

func (m *SimState) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SimState) GetID

func (m *SimState) GetID() uint32

GetID gets the ID of the Message

func (*SimState) GetMessageName

func (m *SimState) GetMessageName() string

GetMessageName gets the name of the Message

func (*SimState) GetVersion

func (m *SimState) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SimState) HasExtensionFields

func (m *SimState) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*SimState) Read

func (m *SimState) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*SimState) String

func (m *SimState) String() string

func (*SimState) Write

func (m *SimState) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type VisionPositionDelta

type VisionPositionDelta struct {
	/*TimeUsec Timestamp (synced to UNIX time or since system boot). */
	TimeUsec uint64
	/*TimeDeltaUsec Time since the last reported camera frame. */
	TimeDeltaUsec uint64
	/*AngleDelta Defines a rotation vector in body frame that rotates the vehicle from the previous to the current orientation. */
	AngleDelta [3]float32
	/*PositionDelta Change in position from previous to current frame rotated into body frame (0=forward, 1=right, 2=down). */
	PositionDelta [3]float32
	/*ConfIDence Normalised confidence value from 0 to 100. */
	ConfIDence float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

VisionPositionDelta Camera vision based attitude and position deltas.

func (*VisionPositionDelta) GetDialect

func (m *VisionPositionDelta) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*VisionPositionDelta) GetID

func (m *VisionPositionDelta) GetID() uint32

GetID gets the ID of the Message

func (*VisionPositionDelta) GetMessageName

func (m *VisionPositionDelta) GetMessageName() string

GetMessageName gets the name of the Message

func (*VisionPositionDelta) GetVersion

func (m *VisionPositionDelta) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*VisionPositionDelta) HasExtensionFields

func (m *VisionPositionDelta) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*VisionPositionDelta) Read

func (m *VisionPositionDelta) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*VisionPositionDelta) String

func (m *VisionPositionDelta) String() string

func (*VisionPositionDelta) Write

func (m *VisionPositionDelta) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

type Wind

type Wind struct {
	/*Direction Wind direction (that wind is coming from). */
	Direction float32
	/*Speed Wind speed in ground plane. */
	Speed float32
	/*SpeedZ Vertical wind speed. */
	SpeedZ float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

Wind Wind estimation.

func (*Wind) GetDialect

func (m *Wind) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*Wind) GetID

func (m *Wind) GetID() uint32

GetID gets the ID of the Message

func (*Wind) GetMessageName

func (m *Wind) GetMessageName() string

GetMessageName gets the name of the Message

func (*Wind) GetVersion

func (m *Wind) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*Wind) HasExtensionFields

func (m *Wind) HasExtensionFields() bool

HasExtensionFields returns true if the message definition contained extensions; false otherwise

func (*Wind) Read

func (m *Wind) Read(frame mavlink2.Frame) (err error)

Read sets the field values of the message from the raw message payload

func (*Wind) String

func (m *Wind) String() string

func (*Wind) Write

func (m *Wind) Write(version int) (output []byte, err error)

Write encodes the field values of the message to a byte array

Jump to

Keyboard shortcuts

? : This menu
/ : Search site
f or F : Jump to
y or Y : Canonical URL