matrixpilot

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: 6 Imported by: 0

Documentation

Index

Constants

View Source
const (
	/*MavPfsCmdReadAll - Read all parameters from storage */
	MavPfsCmdReadAll = 0
	/*MavPfsCmdWriteAll - Write all parameters to storage */
	MavPfsCmdWriteAll = 1
	/*MavPfsCmdClearAll - Clear all  parameters in storage */
	MavPfsCmdClearAll = 2
	/*MavPfsCmdReadSpecific - Read specific parameters from storage */
	MavPfsCmdReadSpecific = 3
	/*MavPfsCmdWriteSpecific - Write specific parameters to storage */
	MavPfsCmdWriteSpecific = 4
	/*MavPfsCmdClearSpecific - Clear specific parameters in storage */
	MavPfsCmdClearSpecific = 5
	/*MavPfsCmdDoNothing - do nothing */
	MavPfsCmdDoNothing = 6
	/*MavPreflightStorageActionEnumEnd -  */
	MavPreflightStorageActionEnumEnd = 7
)

MAV_PREFLIGHT_STORAGE_ACTION - Action required when performing CMD_PREFLIGHT_STORAGE

View Source
const (
	/*MavCmdPreflightStorageAdvanced - Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. */
	MavCmdPreflightStorageAdvanced = 0
	/*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
	/*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
	/*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
	/*MavCmdEnumEnd -  */
	MavCmdEnumEnd = 31015
)

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

Variables

This section is empty.

Functions

This section is empty.

Types

type Airspeeds

type Airspeeds struct {
	/*TimeBootMs Timestamp (milliseconds since system boot) */
	TimeBootMs uint32
	/*AirspeedIMU Airspeed estimate from IMU, cm/s */
	AirspeedIMU int16
	/*AirspeedPitot Pitot measured forward airpseed, cm/s */
	AirspeedPitot int16
	/*AirspeedHotWire Hot wire anenometer measured airspeed, cm/s */
	AirspeedHotWire int16
	/*AirspeedUltrasonic Ultrasonic measured airspeed, cm/s */
	AirspeedUltrasonic int16
	/*Aoa Angle of attack sensor, degrees * 10 */
	Aoa int16
	/*Aoy Yaw angle sensor, degrees * 10 */
	Aoy int16
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

Airspeeds The airspeed measured by sensors and IMU

func (*Airspeeds) GetDialect

func (m *Airspeeds) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*Airspeeds) GetID

func (m *Airspeeds) GetID() uint32

GetID gets the ID of the Message

func (*Airspeeds) GetMessageName

func (m *Airspeeds) GetMessageName() string

GetMessageName gets the name of the Message

func (*Airspeeds) GetVersion

func (m *Airspeeds) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*Airspeeds) HasExtensionFields

func (m *Airspeeds) HasExtensionFields() bool

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

func (*Airspeeds) Read

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

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

func (*Airspeeds) String

func (m *Airspeeds) String() string

func (*Airspeeds) Write

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

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

type Altitudes

type Altitudes struct {
	/*TimeBootMs Timestamp (milliseconds since system boot) */
	TimeBootMs uint32
	/*AltGPS GPS altitude (MSL) in meters, expressed as * 1000 (millimeters) */
	AltGPS int32
	/*AltIMU IMU altitude above ground in meters, expressed as * 1000 (millimeters) */
	AltIMU int32
	/*AltBarometric barometeric altitude above ground in meters, expressed as * 1000 (millimeters) */
	AltBarometric int32
	/*AltOpticalFlow Optical flow altitude above ground in meters, expressed as * 1000 (millimeters) */
	AltOpticalFlow int32
	/*AltRangeFinder Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters) */
	AltRangeFinder int32
	/*AltExtra Extra altitude above ground in meters, expressed as * 1000 (millimeters) */
	AltExtra int32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

Altitudes The altitude measured by sensors and IMU

func (*Altitudes) GetDialect

func (m *Altitudes) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*Altitudes) GetID

func (m *Altitudes) GetID() uint32

GetID gets the ID of the Message

func (*Altitudes) GetMessageName

func (m *Altitudes) GetMessageName() string

GetMessageName gets the name of the Message

func (*Altitudes) GetVersion

func (m *Altitudes) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*Altitudes) HasExtensionFields

func (m *Altitudes) HasExtensionFields() bool

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

func (*Altitudes) Read

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

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

func (*Altitudes) String

func (m *Altitudes) String() string

func (*Altitudes) Write

func (m *Altitudes) 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 FlexifunctionBufferFunction

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

FlexifunctionBufferFunction Flexifunction type and parameters for component at function index from buffer

func (*FlexifunctionBufferFunction) GetDialect

func (m *FlexifunctionBufferFunction) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*FlexifunctionBufferFunction) GetID

GetID gets the ID of the Message

func (*FlexifunctionBufferFunction) GetMessageName

func (m *FlexifunctionBufferFunction) GetMessageName() string

GetMessageName gets the name of the Message

func (*FlexifunctionBufferFunction) GetVersion

func (m *FlexifunctionBufferFunction) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*FlexifunctionBufferFunction) HasExtensionFields

func (m *FlexifunctionBufferFunction) HasExtensionFields() bool

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

func (*FlexifunctionBufferFunction) Read

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

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

func (*FlexifunctionBufferFunction) String

func (m *FlexifunctionBufferFunction) String() string

func (*FlexifunctionBufferFunction) Write

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

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

type FlexifunctionBufferFunctionAck

type FlexifunctionBufferFunctionAck struct {
	/*FuncIndex Function index */
	FuncIndex uint16
	/*Result result of acknowledge, 0=fail, 1=good */
	Result uint16
	/*TargetSystem System ID */
	TargetSystem uint8
	/*TargetComponent Component ID */
	TargetComponent uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

FlexifunctionBufferFunctionAck Flexifunction type and parameters for component at function index from buffer

func (*FlexifunctionBufferFunctionAck) GetDialect

func (m *FlexifunctionBufferFunctionAck) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*FlexifunctionBufferFunctionAck) GetID

GetID gets the ID of the Message

func (*FlexifunctionBufferFunctionAck) GetMessageName

func (m *FlexifunctionBufferFunctionAck) GetMessageName() string

GetMessageName gets the name of the Message

func (*FlexifunctionBufferFunctionAck) GetVersion

func (m *FlexifunctionBufferFunctionAck) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*FlexifunctionBufferFunctionAck) HasExtensionFields

func (m *FlexifunctionBufferFunctionAck) HasExtensionFields() bool

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

func (*FlexifunctionBufferFunctionAck) Read

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

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

func (*FlexifunctionBufferFunctionAck) String

func (*FlexifunctionBufferFunctionAck) Write

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

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

type FlexifunctionCommand

type FlexifunctionCommand struct {
	/*TargetSystem System ID */
	TargetSystem uint8
	/*TargetComponent Component ID */
	TargetComponent uint8
	/*CommandType Flexifunction command type */
	CommandType uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

FlexifunctionCommand Acknowldge sucess or failure of a flexifunction command

func (*FlexifunctionCommand) GetDialect

func (m *FlexifunctionCommand) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*FlexifunctionCommand) GetID

func (m *FlexifunctionCommand) GetID() uint32

GetID gets the ID of the Message

func (*FlexifunctionCommand) GetMessageName

func (m *FlexifunctionCommand) GetMessageName() string

GetMessageName gets the name of the Message

func (*FlexifunctionCommand) GetVersion

func (m *FlexifunctionCommand) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*FlexifunctionCommand) HasExtensionFields

func (m *FlexifunctionCommand) HasExtensionFields() bool

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

func (*FlexifunctionCommand) Read

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

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

func (*FlexifunctionCommand) String

func (m *FlexifunctionCommand) String() string

func (*FlexifunctionCommand) Write

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

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

type FlexifunctionCommandAck

type FlexifunctionCommandAck struct {
	/*CommandType Command acknowledged */
	CommandType uint16
	/*Result result of acknowledge */
	Result uint16
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

FlexifunctionCommandAck Acknowldge sucess or failure of a flexifunction command

func (*FlexifunctionCommandAck) GetDialect

func (m *FlexifunctionCommandAck) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*FlexifunctionCommandAck) GetID

func (m *FlexifunctionCommandAck) GetID() uint32

GetID gets the ID of the Message

func (*FlexifunctionCommandAck) GetMessageName

func (m *FlexifunctionCommandAck) GetMessageName() string

GetMessageName gets the name of the Message

func (*FlexifunctionCommandAck) GetVersion

func (m *FlexifunctionCommandAck) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*FlexifunctionCommandAck) HasExtensionFields

func (m *FlexifunctionCommandAck) HasExtensionFields() bool

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

func (*FlexifunctionCommandAck) Read

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

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

func (*FlexifunctionCommandAck) String

func (m *FlexifunctionCommandAck) String() string

func (*FlexifunctionCommandAck) Write

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

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

type FlexifunctionDirectory

type FlexifunctionDirectory struct {
	/*TargetSystem System ID */
	TargetSystem uint8
	/*TargetComponent Component ID */
	TargetComponent uint8
	/*DirectoryType 0=inputs, 1=outputs */
	DirectoryType uint8
	/*StartIndex index of first directory entry to write */
	StartIndex uint8
	/*Count count of directory entries to write */
	Count uint8
	/*DirectoryData Settings data */
	DirectoryData [48]int8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

FlexifunctionDirectory Acknowldge sucess or failure of a flexifunction command

func (*FlexifunctionDirectory) GetDialect

func (m *FlexifunctionDirectory) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*FlexifunctionDirectory) GetID

func (m *FlexifunctionDirectory) GetID() uint32

GetID gets the ID of the Message

func (*FlexifunctionDirectory) GetMessageName

func (m *FlexifunctionDirectory) GetMessageName() string

GetMessageName gets the name of the Message

func (*FlexifunctionDirectory) GetVersion

func (m *FlexifunctionDirectory) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*FlexifunctionDirectory) HasExtensionFields

func (m *FlexifunctionDirectory) HasExtensionFields() bool

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

func (*FlexifunctionDirectory) Read

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

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

func (*FlexifunctionDirectory) String

func (m *FlexifunctionDirectory) String() string

func (*FlexifunctionDirectory) Write

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

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

type FlexifunctionDirectoryAck

type FlexifunctionDirectoryAck struct {
	/*Result result of acknowledge, 0=fail, 1=good */
	Result uint16
	/*TargetSystem System ID */
	TargetSystem uint8
	/*TargetComponent Component ID */
	TargetComponent uint8
	/*DirectoryType 0=inputs, 1=outputs */
	DirectoryType uint8
	/*StartIndex index of first directory entry to write */
	StartIndex uint8
	/*Count count of directory entries to write */
	Count uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

FlexifunctionDirectoryAck Acknowldge sucess or failure of a flexifunction command

func (*FlexifunctionDirectoryAck) GetDialect

func (m *FlexifunctionDirectoryAck) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*FlexifunctionDirectoryAck) GetID

func (m *FlexifunctionDirectoryAck) GetID() uint32

GetID gets the ID of the Message

func (*FlexifunctionDirectoryAck) GetMessageName

func (m *FlexifunctionDirectoryAck) GetMessageName() string

GetMessageName gets the name of the Message

func (*FlexifunctionDirectoryAck) GetVersion

func (m *FlexifunctionDirectoryAck) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*FlexifunctionDirectoryAck) HasExtensionFields

func (m *FlexifunctionDirectoryAck) HasExtensionFields() bool

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

func (*FlexifunctionDirectoryAck) Read

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

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

func (*FlexifunctionDirectoryAck) String

func (m *FlexifunctionDirectoryAck) String() string

func (*FlexifunctionDirectoryAck) Write

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

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

type FlexifunctionReadReq

type FlexifunctionReadReq struct {
	/*ReadReqType Type of flexifunction data requested */
	ReadReqType int16
	/*DataIndex index into data where needed */
	DataIndex int16
	/*TargetSystem System ID */
	TargetSystem uint8
	/*TargetComponent Component ID */
	TargetComponent uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

FlexifunctionReadReq Reqest reading of flexifunction data

func (*FlexifunctionReadReq) GetDialect

func (m *FlexifunctionReadReq) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*FlexifunctionReadReq) GetID

func (m *FlexifunctionReadReq) GetID() uint32

GetID gets the ID of the Message

func (*FlexifunctionReadReq) GetMessageName

func (m *FlexifunctionReadReq) GetMessageName() string

GetMessageName gets the name of the Message

func (*FlexifunctionReadReq) GetVersion

func (m *FlexifunctionReadReq) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*FlexifunctionReadReq) HasExtensionFields

func (m *FlexifunctionReadReq) HasExtensionFields() bool

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

func (*FlexifunctionReadReq) Read

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

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

func (*FlexifunctionReadReq) String

func (m *FlexifunctionReadReq) String() string

func (*FlexifunctionReadReq) Write

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

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

type FlexifunctionSet

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

FlexifunctionSet Depreciated but used as a compiler flag. Do not remove

func (*FlexifunctionSet) GetDialect

func (m *FlexifunctionSet) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*FlexifunctionSet) GetID

func (m *FlexifunctionSet) GetID() uint32

GetID gets the ID of the Message

func (*FlexifunctionSet) GetMessageName

func (m *FlexifunctionSet) GetMessageName() string

GetMessageName gets the name of the Message

func (*FlexifunctionSet) GetVersion

func (m *FlexifunctionSet) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*FlexifunctionSet) HasExtensionFields

func (m *FlexifunctionSet) HasExtensionFields() bool

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

func (*FlexifunctionSet) Read

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

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

func (*FlexifunctionSet) String

func (m *FlexifunctionSet) String() string

func (*FlexifunctionSet) Write

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

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

type SerialUdbExtraF13

type SerialUdbExtraF13 struct {
	/*SueLatOrigin Serial UDB Extra MP Origin Latitude */
	SueLatOrigin int32
	/*SueLonOrigin Serial UDB Extra MP Origin Longitude */
	SueLonOrigin int32
	/*SueAltOrigin Serial UDB Extra MP Origin Altitude Above Sea Level */
	SueAltOrigin int32
	/*SueWeekNo Serial UDB Extra GPS Week Number */
	SueWeekNo int16
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF13 Backwards compatible version of SERIAL_UDB_EXTRA F13: format

func (*SerialUdbExtraF13) GetDialect

func (m *SerialUdbExtraF13) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF13) GetID

func (m *SerialUdbExtraF13) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF13) GetMessageName

func (m *SerialUdbExtraF13) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF13) GetVersion

func (m *SerialUdbExtraF13) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF13) HasExtensionFields

func (m *SerialUdbExtraF13) HasExtensionFields() bool

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

func (*SerialUdbExtraF13) Read

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

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

func (*SerialUdbExtraF13) String

func (m *SerialUdbExtraF13) String() string

func (*SerialUdbExtraF13) Write

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

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

type SerialUdbExtraF14

type SerialUdbExtraF14 struct {
	/*SueTrapSouRCe Serial UDB Extra Type Program Address of Last Trap */
	SueTrapSouRCe uint32
	/*SueRCon Serial UDB Extra Reboot Register of DSPIC */
	SueRCon int16
	/*SueTrapFlags Serial UDB Extra  Last dspic Trap Flags */
	SueTrapFlags int16
	/*SueOscFailCount Serial UDB Extra Number of Ocillator Failures */
	SueOscFailCount int16
	/*SueWindEstimation Serial UDB Extra Wind Estimation Enabled */
	SueWindEstimation uint8
	/*SueGPSType Serial UDB Extra Type of GPS Unit */
	SueGPSType uint8
	/*SueDr Serial UDB Extra Dead Reckoning Enabled */
	SueDr uint8
	/*SueBoardType Serial UDB Extra Type of UDB Hardware */
	SueBoardType uint8
	/*SueAirframe Serial UDB Extra Type of Airframe */
	SueAirframe uint8
	/*SueClockConfig Serial UDB Extra UDB Internal Clock Configuration */
	SueClockConfig uint8
	/*SueFlightPlanType Serial UDB Extra Type of Flight Plan */
	SueFlightPlanType uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF14 Backwards compatible version of SERIAL_UDB_EXTRA F14: format

func (*SerialUdbExtraF14) GetDialect

func (m *SerialUdbExtraF14) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF14) GetID

func (m *SerialUdbExtraF14) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF14) GetMessageName

func (m *SerialUdbExtraF14) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF14) GetVersion

func (m *SerialUdbExtraF14) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF14) HasExtensionFields

func (m *SerialUdbExtraF14) HasExtensionFields() bool

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

func (*SerialUdbExtraF14) Read

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

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

func (*SerialUdbExtraF14) String

func (m *SerialUdbExtraF14) String() string

func (*SerialUdbExtraF14) Write

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

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

type SerialUdbExtraF15

type SerialUdbExtraF15 struct {
	/*SueIDVehicleModelName Serial UDB Extra Model Name Of Vehicle */
	SueIDVehicleModelName [40]uint8
	/*SueIDVehicleRegistration Serial UDB Extra Registraton Number of Vehicle */
	SueIDVehicleRegistration [20]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF15 Backwards compatible version of SERIAL_UDB_EXTRA F15 format

func (*SerialUdbExtraF15) GetDialect

func (m *SerialUdbExtraF15) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF15) GetID

func (m *SerialUdbExtraF15) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF15) GetMessageName

func (m *SerialUdbExtraF15) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF15) GetVersion

func (m *SerialUdbExtraF15) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF15) HasExtensionFields

func (m *SerialUdbExtraF15) HasExtensionFields() bool

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

func (*SerialUdbExtraF15) Read

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

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

func (*SerialUdbExtraF15) String

func (m *SerialUdbExtraF15) String() string

func (*SerialUdbExtraF15) Write

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

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

type SerialUdbExtraF16

type SerialUdbExtraF16 struct {
	/*SueIDLeadPilot Serial UDB Extra Name of Expected Lead Pilot */
	SueIDLeadPilot [40]uint8
	/*SueIDDiyDronesURL Serial UDB Extra URL of Lead Pilot or Team */
	SueIDDiyDronesURL [70]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF16 Backwards compatible version of SERIAL_UDB_EXTRA F16 format

func (*SerialUdbExtraF16) GetDialect

func (m *SerialUdbExtraF16) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF16) GetID

func (m *SerialUdbExtraF16) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF16) GetMessageName

func (m *SerialUdbExtraF16) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF16) GetVersion

func (m *SerialUdbExtraF16) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF16) HasExtensionFields

func (m *SerialUdbExtraF16) HasExtensionFields() bool

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

func (*SerialUdbExtraF16) Read

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

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

func (*SerialUdbExtraF16) String

func (m *SerialUdbExtraF16) String() string

func (*SerialUdbExtraF16) Write

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

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

type SerialUdbExtraF17

type SerialUdbExtraF17 struct {
	/*SueFeedForward SUE Feed Forward Gain */
	SueFeedForward float32
	/*SueTurnRateNAV SUE Max Turn Rate when Navigating */
	SueTurnRateNAV float32
	/*SueTurnRateFbw SUE Max Turn Rate in Fly By Wire Mode */
	SueTurnRateFbw float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF17 Backwards compatible version of SERIAL_UDB_EXTRA F17 format

func (*SerialUdbExtraF17) GetDialect

func (m *SerialUdbExtraF17) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF17) GetID

func (m *SerialUdbExtraF17) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF17) GetMessageName

func (m *SerialUdbExtraF17) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF17) GetVersion

func (m *SerialUdbExtraF17) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF17) HasExtensionFields

func (m *SerialUdbExtraF17) HasExtensionFields() bool

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

func (*SerialUdbExtraF17) Read

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

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

func (*SerialUdbExtraF17) String

func (m *SerialUdbExtraF17) String() string

func (*SerialUdbExtraF17) Write

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

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

type SerialUdbExtraF18

type SerialUdbExtraF18 struct {
	/*AngleOfAttackNormal SUE Angle of Attack Normal */
	AngleOfAttackNormal float32
	/*AngleOfAttackInverted SUE Angle of Attack Inverted */
	AngleOfAttackInverted float32
	/*ElevatorTrimNormal SUE Elevator Trim Normal */
	ElevatorTrimNormal float32
	/*ElevatorTrimInverted SUE Elevator Trim Inverted */
	ElevatorTrimInverted float32
	/*ReferenceSpeed SUE reference_speed */
	ReferenceSpeed float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF18 Backwards compatible version of SERIAL_UDB_EXTRA F18 format

func (*SerialUdbExtraF18) GetDialect

func (m *SerialUdbExtraF18) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF18) GetID

func (m *SerialUdbExtraF18) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF18) GetMessageName

func (m *SerialUdbExtraF18) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF18) GetVersion

func (m *SerialUdbExtraF18) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF18) HasExtensionFields

func (m *SerialUdbExtraF18) HasExtensionFields() bool

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

func (*SerialUdbExtraF18) Read

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

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

func (*SerialUdbExtraF18) String

func (m *SerialUdbExtraF18) String() string

func (*SerialUdbExtraF18) Write

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

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

type SerialUdbExtraF19

type SerialUdbExtraF19 struct {
	/*SueAileronOutputChannel SUE aileron output channel */
	SueAileronOutputChannel uint8
	/*SueAileronReversed SUE aileron reversed */
	SueAileronReversed uint8
	/*SueElevatorOutputChannel SUE elevator output channel */
	SueElevatorOutputChannel uint8
	/*SueElevatorReversed SUE elevator reversed */
	SueElevatorReversed uint8
	/*SueThrottleOutputChannel SUE throttle output channel */
	SueThrottleOutputChannel uint8
	/*SueThrottleReversed SUE throttle reversed */
	SueThrottleReversed uint8
	/*SueRudderOutputChannel SUE rudder output channel */
	SueRudderOutputChannel uint8
	/*SueRudderReversed SUE rudder reversed */
	SueRudderReversed uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF19 Backwards compatible version of SERIAL_UDB_EXTRA F19 format

func (*SerialUdbExtraF19) GetDialect

func (m *SerialUdbExtraF19) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF19) GetID

func (m *SerialUdbExtraF19) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF19) GetMessageName

func (m *SerialUdbExtraF19) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF19) GetVersion

func (m *SerialUdbExtraF19) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF19) HasExtensionFields

func (m *SerialUdbExtraF19) HasExtensionFields() bool

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

func (*SerialUdbExtraF19) Read

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

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

func (*SerialUdbExtraF19) String

func (m *SerialUdbExtraF19) String() string

func (*SerialUdbExtraF19) Write

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

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

type SerialUdbExtraF20

type SerialUdbExtraF20 struct {
	/*SueTrimValueInput1 SUE UDB PWM Trim Value on Input 1 */
	SueTrimValueInput1 int16
	/*SueTrimValueInput2 SUE UDB PWM Trim Value on Input 2 */
	SueTrimValueInput2 int16
	/*SueTrimValueInput3 SUE UDB PWM Trim Value on Input 3 */
	SueTrimValueInput3 int16
	/*SueTrimValueInput4 SUE UDB PWM Trim Value on Input 4 */
	SueTrimValueInput4 int16
	/*SueTrimValueInput5 SUE UDB PWM Trim Value on Input 5 */
	SueTrimValueInput5 int16
	/*SueTrimValueInput6 SUE UDB PWM Trim Value on Input 6 */
	SueTrimValueInput6 int16
	/*SueTrimValueInput7 SUE UDB PWM Trim Value on Input 7 */
	SueTrimValueInput7 int16
	/*SueTrimValueInput8 SUE UDB PWM Trim Value on Input 8 */
	SueTrimValueInput8 int16
	/*SueTrimValueInput9 SUE UDB PWM Trim Value on Input 9 */
	SueTrimValueInput9 int16
	/*SueTrimValueInput10 SUE UDB PWM Trim Value on Input 10 */
	SueTrimValueInput10 int16
	/*SueTrimValueInput11 SUE UDB PWM Trim Value on Input 11 */
	SueTrimValueInput11 int16
	/*SueTrimValueInput12 SUE UDB PWM Trim Value on Input 12 */
	SueTrimValueInput12 int16
	/*SueNumberOfInputs SUE Number of Input Channels */
	SueNumberOfInputs uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF20 Backwards compatible version of SERIAL_UDB_EXTRA F20 format

func (*SerialUdbExtraF20) GetDialect

func (m *SerialUdbExtraF20) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF20) GetID

func (m *SerialUdbExtraF20) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF20) GetMessageName

func (m *SerialUdbExtraF20) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF20) GetVersion

func (m *SerialUdbExtraF20) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF20) HasExtensionFields

func (m *SerialUdbExtraF20) HasExtensionFields() bool

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

func (*SerialUdbExtraF20) Read

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

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

func (*SerialUdbExtraF20) String

func (m *SerialUdbExtraF20) String() string

func (*SerialUdbExtraF20) Write

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

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

type SerialUdbExtraF21

type SerialUdbExtraF21 struct {
	/*SueAccelXOffset SUE X accelerometer offset */
	SueAccelXOffset int16
	/*SueAccelYOffset SUE Y accelerometer offset */
	SueAccelYOffset int16
	/*SueAccelZOffset SUE Z accelerometer offset */
	SueAccelZOffset int16
	/*SueGyroXOffset SUE X gyro offset */
	SueGyroXOffset int16
	/*SueGyroYOffset SUE Y gyro offset */
	SueGyroYOffset int16
	/*SueGyroZOffset SUE Z gyro offset */
	SueGyroZOffset int16
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF21 Backwards compatible version of SERIAL_UDB_EXTRA F21 format

func (*SerialUdbExtraF21) GetDialect

func (m *SerialUdbExtraF21) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF21) GetID

func (m *SerialUdbExtraF21) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF21) GetMessageName

func (m *SerialUdbExtraF21) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF21) GetVersion

func (m *SerialUdbExtraF21) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF21) HasExtensionFields

func (m *SerialUdbExtraF21) HasExtensionFields() bool

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

func (*SerialUdbExtraF21) Read

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

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

func (*SerialUdbExtraF21) String

func (m *SerialUdbExtraF21) String() string

func (*SerialUdbExtraF21) Write

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

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

type SerialUdbExtraF22

type SerialUdbExtraF22 struct {
	/*SueAccelXAtCalibration SUE X accelerometer at calibration time */
	SueAccelXAtCalibration int16
	/*SueAccelYAtCalibration SUE Y accelerometer at calibration time */
	SueAccelYAtCalibration int16
	/*SueAccelZAtCalibration SUE Z accelerometer at calibration time */
	SueAccelZAtCalibration int16
	/*SueGyroXAtCalibration SUE X gyro at calibration time */
	SueGyroXAtCalibration int16
	/*SueGyroYAtCalibration SUE Y gyro at calibration time */
	SueGyroYAtCalibration int16
	/*SueGyroZAtCalibration SUE Z gyro at calibration time */
	SueGyroZAtCalibration int16
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF22 Backwards compatible version of SERIAL_UDB_EXTRA F22 format

func (*SerialUdbExtraF22) GetDialect

func (m *SerialUdbExtraF22) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF22) GetID

func (m *SerialUdbExtraF22) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF22) GetMessageName

func (m *SerialUdbExtraF22) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF22) GetVersion

func (m *SerialUdbExtraF22) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF22) HasExtensionFields

func (m *SerialUdbExtraF22) HasExtensionFields() bool

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

func (*SerialUdbExtraF22) Read

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

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

func (*SerialUdbExtraF22) String

func (m *SerialUdbExtraF22) String() string

func (*SerialUdbExtraF22) Write

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

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

type SerialUdbExtraF2A

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

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

func (*SerialUdbExtraF2A) GetDialect

func (m *SerialUdbExtraF2A) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF2A) GetID

func (m *SerialUdbExtraF2A) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF2A) GetMessageName

func (m *SerialUdbExtraF2A) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF2A) GetVersion

func (m *SerialUdbExtraF2A) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF2A) HasExtensionFields

func (m *SerialUdbExtraF2A) HasExtensionFields() bool

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

func (*SerialUdbExtraF2A) Read

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

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

func (*SerialUdbExtraF2A) String

func (m *SerialUdbExtraF2A) String() string

func (*SerialUdbExtraF2A) Write

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

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

type SerialUdbExtraF2B

type SerialUdbExtraF2B struct {
	/*SueTime Serial UDB Extra Time */
	SueTime uint32
	/*SueFlags Serial UDB Extra Status Flags */
	SueFlags uint32
	/*SueBaromPress SUE barometer pressure */
	SueBaromPress int32
	/*SueBaromAlt SUE barometer altitude */
	SueBaromAlt int32
	/*SuePwmInput1 Serial UDB Extra PWM Input Channel 1 */
	SuePwmInput1 int16
	/*SuePwmInput2 Serial UDB Extra PWM Input Channel 2 */
	SuePwmInput2 int16
	/*SuePwmInput3 Serial UDB Extra PWM Input Channel 3 */
	SuePwmInput3 int16
	/*SuePwmInput4 Serial UDB Extra PWM Input Channel 4 */
	SuePwmInput4 int16
	/*SuePwmInput5 Serial UDB Extra PWM Input Channel 5 */
	SuePwmInput5 int16
	/*SuePwmInput6 Serial UDB Extra PWM Input Channel 6 */
	SuePwmInput6 int16
	/*SuePwmInput7 Serial UDB Extra PWM Input Channel 7 */
	SuePwmInput7 int16
	/*SuePwmInput8 Serial UDB Extra PWM Input Channel 8 */
	SuePwmInput8 int16
	/*SuePwmInput9 Serial UDB Extra PWM Input Channel 9 */
	SuePwmInput9 int16
	/*SuePwmInput10 Serial UDB Extra PWM Input Channel 10 */
	SuePwmInput10 int16
	/*SuePwmInput11 Serial UDB Extra PWM Input Channel 11 */
	SuePwmInput11 int16
	/*SuePwmInput12 Serial UDB Extra PWM Input Channel 12 */
	SuePwmInput12 int16
	/*SuePwmOutput1 Serial UDB Extra PWM Output Channel 1 */
	SuePwmOutput1 int16
	/*SuePwmOutput2 Serial UDB Extra PWM Output Channel 2 */
	SuePwmOutput2 int16
	/*SuePwmOutput3 Serial UDB Extra PWM Output Channel 3 */
	SuePwmOutput3 int16
	/*SuePwmOutput4 Serial UDB Extra PWM Output Channel 4 */
	SuePwmOutput4 int16
	/*SuePwmOutput5 Serial UDB Extra PWM Output Channel 5 */
	SuePwmOutput5 int16
	/*SuePwmOutput6 Serial UDB Extra PWM Output Channel 6 */
	SuePwmOutput6 int16
	/*SuePwmOutput7 Serial UDB Extra PWM Output Channel 7 */
	SuePwmOutput7 int16
	/*SuePwmOutput8 Serial UDB Extra PWM Output Channel 8 */
	SuePwmOutput8 int16
	/*SuePwmOutput9 Serial UDB Extra PWM Output Channel 9 */
	SuePwmOutput9 int16
	/*SuePwmOutput10 Serial UDB Extra PWM Output Channel 10 */
	SuePwmOutput10 int16
	/*SuePwmOutput11 Serial UDB Extra PWM Output Channel 11 */
	SuePwmOutput11 int16
	/*SuePwmOutput12 Serial UDB Extra PWM Output Channel 12 */
	SuePwmOutput12 int16
	/*SueIMULocationX Serial UDB Extra IMU Location X */
	SueIMULocationX int16
	/*SueIMULocationY Serial UDB Extra IMU Location Y */
	SueIMULocationY int16
	/*SueIMULocationZ Serial UDB Extra IMU Location Z */
	SueIMULocationZ int16
	/*SueLocationErrorEarthX Serial UDB Location Error Earth X */
	SueLocationErrorEarthX int16
	/*SueLocationErrorEarthY Serial UDB Location Error Earth Y */
	SueLocationErrorEarthY int16
	/*SueLocationErrorEarthZ Serial UDB Location Error Earth Z */
	SueLocationErrorEarthZ int16
	/*SueOscFails Serial UDB Extra Oscillator Failure Count */
	SueOscFails int16
	/*SueIMUVelocityX Serial UDB Extra IMU Velocity X */
	SueIMUVelocityX int16
	/*SueIMUVelocityY Serial UDB Extra IMU Velocity Y */
	SueIMUVelocityY int16
	/*SueIMUVelocityZ Serial UDB Extra IMU Velocity Z */
	SueIMUVelocityZ int16
	/*SueWaypointGoalX Serial UDB Extra Current Waypoint Goal X */
	SueWaypointGoalX int16
	/*SueWaypointGoalY Serial UDB Extra Current Waypoint Goal Y */
	SueWaypointGoalY int16
	/*SueWaypointGoalZ Serial UDB Extra Current Waypoint Goal Z */
	SueWaypointGoalZ int16
	/*SueAeroX Aeroforce in UDB X Axis */
	SueAeroX int16
	/*SueAeroY Aeroforce in UDB Y Axis */
	SueAeroY int16
	/*SueAeroZ Aeroforce in UDB Z axis */
	SueAeroZ int16
	/*SueBaromTemp SUE barometer temperature */
	SueBaromTemp int16
	/*SueBatVolt SUE battery voltage */
	SueBatVolt int16
	/*SueBatAmp SUE battery current */
	SueBatAmp int16
	/*SueBatAmpHours SUE battery milli amp hours used */
	SueBatAmpHours int16
	/*SueDesiredHeight Sue autopilot desired height */
	SueDesiredHeight int16
	/*SueMemoryStackFree Serial UDB Extra Stack Memory Free */
	SueMemoryStackFree int16
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF2B Backwards compatible version of SERIAL_UDB_EXTRA - F2: Part B

func (*SerialUdbExtraF2B) GetDialect

func (m *SerialUdbExtraF2B) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF2B) GetID

func (m *SerialUdbExtraF2B) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF2B) GetMessageName

func (m *SerialUdbExtraF2B) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF2B) GetVersion

func (m *SerialUdbExtraF2B) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF2B) HasExtensionFields

func (m *SerialUdbExtraF2B) HasExtensionFields() bool

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

func (*SerialUdbExtraF2B) Read

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

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

func (*SerialUdbExtraF2B) String

func (m *SerialUdbExtraF2B) String() string

func (*SerialUdbExtraF2B) Write

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

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

type SerialUdbExtraF4

type SerialUdbExtraF4 struct {
	/*SueRollStabilizationAilerons Serial UDB Extra Roll Stabilization with Ailerons Enabled */
	SueRollStabilizationAilerons uint8
	/*SueRollStabilizationRudder Serial UDB Extra Roll Stabilization with Rudder Enabled */
	SueRollStabilizationRudder uint8
	/*SuePitchStabilization Serial UDB Extra Pitch Stabilization Enabled */
	SuePitchStabilization uint8
	/*SueYawStabilizationRudder Serial UDB Extra Yaw Stabilization using Rudder Enabled */
	SueYawStabilizationRudder uint8
	/*SueYawStabilizationAileron Serial UDB Extra Yaw Stabilization using Ailerons Enabled */
	SueYawStabilizationAileron uint8
	/*SueAileronNAVigation Serial UDB Extra Navigation with Ailerons Enabled */
	SueAileronNAVigation uint8
	/*SueRudderNAVigation Serial UDB Extra Navigation with Rudder Enabled */
	SueRudderNAVigation uint8
	/*SueAltitudeholdStabilized Serial UDB Extra Type of Alitude Hold when in Stabilized Mode */
	SueAltitudeholdStabilized uint8
	/*SueAltitudeholdWaypoint Serial UDB Extra Type of Alitude Hold when in Waypoint Mode */
	SueAltitudeholdWaypoint uint8
	/*SueRacingMode Serial UDB Extra Firmware racing mode enabled */
	SueRacingMode uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF4 Backwards compatible version of SERIAL_UDB_EXTRA F4: format

func (*SerialUdbExtraF4) GetDialect

func (m *SerialUdbExtraF4) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF4) GetID

func (m *SerialUdbExtraF4) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF4) GetMessageName

func (m *SerialUdbExtraF4) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF4) GetVersion

func (m *SerialUdbExtraF4) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF4) HasExtensionFields

func (m *SerialUdbExtraF4) HasExtensionFields() bool

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

func (*SerialUdbExtraF4) Read

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

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

func (*SerialUdbExtraF4) String

func (m *SerialUdbExtraF4) String() string

func (*SerialUdbExtraF4) Write

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

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

type SerialUdbExtraF5

type SerialUdbExtraF5 struct {
	/*SueYawkpAileron Serial UDB YAWKP_AILERON Gain for Proporional control of navigation */
	SueYawkpAileron float32
	/*SueYawkdAileron Serial UDB YAWKD_AILERON Gain for Rate control of navigation */
	SueYawkdAileron float32
	/*SueRollkp Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization */
	SueRollkp float32
	/*SueRollkd Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization */
	SueRollkd float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF5 Backwards compatible version of SERIAL_UDB_EXTRA F5: format

func (*SerialUdbExtraF5) GetDialect

func (m *SerialUdbExtraF5) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF5) GetID

func (m *SerialUdbExtraF5) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF5) GetMessageName

func (m *SerialUdbExtraF5) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF5) GetVersion

func (m *SerialUdbExtraF5) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF5) HasExtensionFields

func (m *SerialUdbExtraF5) HasExtensionFields() bool

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

func (*SerialUdbExtraF5) Read

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

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

func (*SerialUdbExtraF5) String

func (m *SerialUdbExtraF5) String() string

func (*SerialUdbExtraF5) Write

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

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

type SerialUdbExtraF6

type SerialUdbExtraF6 struct {
	/*SuePitchgain Serial UDB Extra PITCHGAIN Proportional Control */
	SuePitchgain float32
	/*SuePitchkd Serial UDB Extra Pitch Rate Control */
	SuePitchkd float32
	/*SueRudderElevMix Serial UDB Extra Rudder to Elevator Mix */
	SueRudderElevMix float32
	/*SueRollElevMix Serial UDB Extra Roll to Elevator Mix */
	SueRollElevMix float32
	/*SueElevatorBoost Gain For Boosting Manual Elevator control When Plane Stabilized */
	SueElevatorBoost float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF6 Backwards compatible version of SERIAL_UDB_EXTRA F6: format

func (*SerialUdbExtraF6) GetDialect

func (m *SerialUdbExtraF6) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF6) GetID

func (m *SerialUdbExtraF6) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF6) GetMessageName

func (m *SerialUdbExtraF6) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF6) GetVersion

func (m *SerialUdbExtraF6) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF6) HasExtensionFields

func (m *SerialUdbExtraF6) HasExtensionFields() bool

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

func (*SerialUdbExtraF6) Read

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

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

func (*SerialUdbExtraF6) String

func (m *SerialUdbExtraF6) String() string

func (*SerialUdbExtraF6) Write

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

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

type SerialUdbExtraF7

type SerialUdbExtraF7 struct {
	/*SueYawkpRudder Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation */
	SueYawkpRudder float32
	/*SueYawkdRudder Serial UDB YAWKD_RUDDER Gain for Rate control of navigation */
	SueYawkdRudder float32
	/*SueRollkpRudder Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization */
	SueRollkpRudder float32
	/*SueRollkdRudder Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization */
	SueRollkdRudder float32
	/*SueRudderBoost SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized */
	SueRudderBoost float32
	/*SueRtlPitchDown Serial UDB Extra Return To Landing - Angle to Pitch Plane Down */
	SueRtlPitchDown float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF7 Backwards compatible version of SERIAL_UDB_EXTRA F7: format

func (*SerialUdbExtraF7) GetDialect

func (m *SerialUdbExtraF7) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF7) GetID

func (m *SerialUdbExtraF7) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF7) GetMessageName

func (m *SerialUdbExtraF7) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF7) GetVersion

func (m *SerialUdbExtraF7) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF7) HasExtensionFields

func (m *SerialUdbExtraF7) HasExtensionFields() bool

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

func (*SerialUdbExtraF7) Read

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

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

func (*SerialUdbExtraF7) String

func (m *SerialUdbExtraF7) String() string

func (*SerialUdbExtraF7) Write

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

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

type SerialUdbExtraF8

type SerialUdbExtraF8 struct {
	/*SueHeightTargetMax Serial UDB Extra HEIGHT_TARGET_MAX */
	SueHeightTargetMax float32
	/*SueHeightTargetMin Serial UDB Extra HEIGHT_TARGET_MIN */
	SueHeightTargetMin float32
	/*SueAltHoldThrottleMin Serial UDB Extra ALT_HOLD_THROTTLE_MIN */
	SueAltHoldThrottleMin float32
	/*SueAltHoldThrottleMax Serial UDB Extra ALT_HOLD_THROTTLE_MAX */
	SueAltHoldThrottleMax float32
	/*SueAltHoldPitchMin Serial UDB Extra ALT_HOLD_PITCH_MIN */
	SueAltHoldPitchMin float32
	/*SueAltHoldPitchMax Serial UDB Extra ALT_HOLD_PITCH_MAX */
	SueAltHoldPitchMax float32
	/*SueAltHoldPitchHigh Serial UDB Extra ALT_HOLD_PITCH_HIGH */
	SueAltHoldPitchHigh float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SerialUdbExtraF8 Backwards compatible version of SERIAL_UDB_EXTRA F8: format

func (*SerialUdbExtraF8) GetDialect

func (m *SerialUdbExtraF8) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SerialUdbExtraF8) GetID

func (m *SerialUdbExtraF8) GetID() uint32

GetID gets the ID of the Message

func (*SerialUdbExtraF8) GetMessageName

func (m *SerialUdbExtraF8) GetMessageName() string

GetMessageName gets the name of the Message

func (*SerialUdbExtraF8) GetVersion

func (m *SerialUdbExtraF8) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SerialUdbExtraF8) HasExtensionFields

func (m *SerialUdbExtraF8) HasExtensionFields() bool

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

func (*SerialUdbExtraF8) Read

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

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

func (*SerialUdbExtraF8) String

func (m *SerialUdbExtraF8) String() string

func (*SerialUdbExtraF8) Write

func (m *SerialUdbExtraF8) 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