slugs

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 (
	/*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
	/*MavCmdDoNothing - Does nothing. */
	MavCmdDoNothing = 10001
	/*MavCmdReturnToBase - Return vehicle to base. */
	MavCmdReturnToBase = 10011
	/*MavCmdStopReturnToBase - Stops the vehicle from returning to base and resumes flight.  */
	MavCmdStopReturnToBase = 10012
	/*MavCmdTurnLight - Turns the vehicle's visible or infrared lights on or off. */
	MavCmdTurnLight = 10013
	/*MavCmdGetMIDLevelCommands - Requests vehicle to send current mid-level commands to ground station. */
	MavCmdGetMIDLevelCommands = 10014
	/*MavCmdMIDlevelStorage - Requests storage of mid-level commands. */
	MavCmdMIDlevelStorage = 10015
	/*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

View Source
const (
	/*SlugsModeNone - No change to SLUGS mode. */
	SlugsModeNone = 0
	/*SlugsModeLiftoff - Vehicle is in liftoff mode. */
	SlugsModeLiftoff = 1
	/*SlugsModePassthrough - Vehicle is in passthrough mode, being controlled by a pilot. */
	SlugsModePassthrough = 2
	/*SlugsModeWaypoint - Vehicle is in waypoint mode, navigating to waypoints. */
	SlugsModeWaypoint = 3
	/*SlugsModeMIDLevel - Vehicle is executing mid-level commands. */
	SlugsModeMIDLevel = 4
	/*SlugsModeReturning - Vehicle is returning to the home location. */
	SlugsModeReturning = 5
	/*SlugsModeLanding - Vehicle is landing. */
	SlugsModeLanding = 6
	/*SlugsModeLost - Lost connection with vehicle. */
	SlugsModeLost = 7
	/*SlugsModeSelectivePassthrough - Vehicle is in selective passthrough mode, where selected surfaces are being manually controlled. */
	SlugsModeSelectivePassthrough = 8
	/*SlugsModeIsr - Vehicle is in ISR mode, performing reconaissance at a point specified by ISR_LOCATION message. */
	SlugsModeIsr = 9
	/*SlugsModeLinePatrol - Vehicle is patrolling along lines between waypoints. */
	SlugsModeLinePatrol = 10
	/*SlugsModeGrounded - Vehicle is grounded or an error has occurred. */
	SlugsModeGrounded = 11
	/*SlugsModeEnumEnd -  */
	SlugsModeEnumEnd = 12
)

SLUGS_MODE - Slugs-specific navigation modes.

View Source
const (
	/*ControlSurfaceFlagRightFlap - 0b00000001 Right flap control passes through to pilot console. */
	ControlSurfaceFlagRightFlap = 1
	/*ControlSurfaceFlagLeftFlap - 0b00000010 Left flap control passes through to pilot console. */
	ControlSurfaceFlagLeftFlap = 2
	/*ControlSurfaceFlagRightElevator - 0b00000100 Right elevator control passes through to pilot console. */
	ControlSurfaceFlagRightElevator = 4
	/*ControlSurfaceFlagLeftElevator - 0b00001000 Left elevator control passes through to pilot console. */
	ControlSurfaceFlagLeftElevator = 8
	/*ControlSurfaceFlagRudder - 0b00010000 Rudder control passes through to pilot console. */
	ControlSurfaceFlagRudder = 16
	/*ControlSurfaceFlagRightAileron - 0b00100000 Right aileron control passes through to pilot console. */
	ControlSurfaceFlagRightAileron = 32
	/*ControlSurfaceFlagLeftAileron - 0b01000000 Left aileron control passes through to pilot console. */
	ControlSurfaceFlagLeftAileron = 64
	/*ControlSurfaceFlagThrottle - 0b10000000 Throttle control passes through to pilot console. */
	ControlSurfaceFlagThrottle = 128
	/*ControlSurfaceFlagEnumEnd -  */
	ControlSurfaceFlagEnumEnd = 129
)

CONTROL_SURFACE_FLAG - These flags encode the control surfaces for selective passthrough mode. If a bit is set then the pilot console

has control of the surface, and if not then the autopilot has control of the surface.

Variables

This section is empty.

Functions

This section is empty.

Types

type Boot

type Boot struct {
	/*Version The onboard software version */
	Version uint32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

Boot The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions. This message allows the sensor and control MCUs to communicate version numbers on startup.

func (*Boot) GetDialect

func (m *Boot) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*Boot) GetID

func (m *Boot) GetID() uint32

GetID gets the ID of the Message

func (*Boot) GetMessageName

func (m *Boot) GetMessageName() string

GetMessageName gets the name of the Message

func (*Boot) GetVersion

func (m *Boot) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*Boot) HasExtensionFields

func (m *Boot) HasExtensionFields() bool

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

func (*Boot) Read

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

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

func (*Boot) String

func (m *Boot) String() string

func (*Boot) Write

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

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

type ControlSurface

type ControlSurface struct {
	/*Mcontrol Pending */
	Mcontrol float32
	/*Bcontrol Order to origin */
	Bcontrol float32
	/*Target The system setting the commands */
	Target uint8
	/*IDsurface ID control surface send 0: throttle 1: aileron 2: elevator 3: rudder */
	IDsurface uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

ControlSurface Control for surface; pending and order to origin.

func (*ControlSurface) GetDialect

func (m *ControlSurface) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*ControlSurface) GetID

func (m *ControlSurface) GetID() uint32

GetID gets the ID of the Message

func (*ControlSurface) GetMessageName

func (m *ControlSurface) GetMessageName() string

GetMessageName gets the name of the Message

func (*ControlSurface) GetVersion

func (m *ControlSurface) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*ControlSurface) HasExtensionFields

func (m *ControlSurface) HasExtensionFields() bool

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

func (*ControlSurface) Read

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

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

func (*ControlSurface) String

func (m *ControlSurface) String() string

func (*ControlSurface) Write

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

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

type CpuLoad

type CpuLoad struct {
	/*Batvolt Battery Voltage */
	Batvolt uint16
	/*Sensload Sensor DSC Load */
	Sensload uint8
	/*Ctrlload Control DSC Load */
	Ctrlload uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

CpuLoad Sensor and DSC control loads.

func (*CpuLoad) GetDialect

func (m *CpuLoad) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*CpuLoad) GetID

func (m *CpuLoad) GetID() uint32

GetID gets the ID of the Message

func (*CpuLoad) GetMessageName

func (m *CpuLoad) GetMessageName() string

GetMessageName gets the name of the Message

func (*CpuLoad) GetVersion

func (m *CpuLoad) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*CpuLoad) HasExtensionFields

func (m *CpuLoad) HasExtensionFields() bool

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

func (*CpuLoad) Read

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

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

func (*CpuLoad) String

func (m *CpuLoad) String() string

func (*CpuLoad) Write

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

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

type CtrlSrfcPt

type CtrlSrfcPt struct {
	/*Bitfieldpt Bitfield containing the passthrough configuration, see CONTROL_SURFACE_FLAG ENUM. */
	Bitfieldpt uint16
	/*Target The system setting the commands */
	Target uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

CtrlSrfcPt This message sets the control surfaces for selective passthrough mode.

func (*CtrlSrfcPt) GetDialect

func (m *CtrlSrfcPt) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*CtrlSrfcPt) GetID

func (m *CtrlSrfcPt) GetID() uint32

GetID gets the ID of the Message

func (*CtrlSrfcPt) GetMessageName

func (m *CtrlSrfcPt) GetMessageName() string

GetMessageName gets the name of the Message

func (*CtrlSrfcPt) GetVersion

func (m *CtrlSrfcPt) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*CtrlSrfcPt) HasExtensionFields

func (m *CtrlSrfcPt) HasExtensionFields() bool

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

func (*CtrlSrfcPt) Read

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

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

func (*CtrlSrfcPt) String

func (m *CtrlSrfcPt) String() string

func (*CtrlSrfcPt) Write

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

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

type DataLog

type DataLog struct {
	/*Fl1 Log value 1  */
	Fl1 float32
	/*Fl2 Log value 2  */
	Fl2 float32
	/*Fl3 Log value 3  */
	Fl3 float32
	/*Fl4 Log value 4  */
	Fl4 float32
	/*Fl5 Log value 5  */
	Fl5 float32
	/*Fl6 Log value 6  */
	Fl6 float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

DataLog Configurable data log probes to be used inside Simulink

func (*DataLog) GetDialect

func (m *DataLog) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*DataLog) GetID

func (m *DataLog) GetID() uint32

GetID gets the ID of the Message

func (*DataLog) GetMessageName

func (m *DataLog) GetMessageName() string

GetMessageName gets the name of the Message

func (*DataLog) GetVersion

func (m *DataLog) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*DataLog) HasExtensionFields

func (m *DataLog) HasExtensionFields() bool

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

func (*DataLog) Read

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

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

func (*DataLog) String

func (m *DataLog) String() string

func (*DataLog) Write

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

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

type Diagnostic

type Diagnostic struct {
	/*Diagfl1 Diagnostic float 1 */
	Diagfl1 float32
	/*Diagfl2 Diagnostic float 2 */
	Diagfl2 float32
	/*Diagfl3 Diagnostic float 3 */
	Diagfl3 float32
	/*Diagsh1 Diagnostic short 1 */
	Diagsh1 int16
	/*Diagsh2 Diagnostic short 2 */
	Diagsh2 int16
	/*Diagsh3 Diagnostic short 3 */
	Diagsh3 int16
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

Diagnostic Configurable diagnostic messages.

func (*Diagnostic) GetDialect

func (m *Diagnostic) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*Diagnostic) GetID

func (m *Diagnostic) GetID() uint32

GetID gets the ID of the Message

func (*Diagnostic) GetMessageName

func (m *Diagnostic) GetMessageName() string

GetMessageName gets the name of the Message

func (*Diagnostic) GetVersion

func (m *Diagnostic) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*Diagnostic) HasExtensionFields

func (m *Diagnostic) HasExtensionFields() bool

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

func (*Diagnostic) Read

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

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

func (*Diagnostic) String

func (m *Diagnostic) String() string

func (*Diagnostic) Write

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

type GPSDateTime struct {
	/*Year Year reported by Gps  */
	Year uint8
	/*Month Month reported by Gps  */
	Month uint8
	/*Day Day reported by Gps  */
	Day uint8
	/*Hour Hour reported by Gps  */
	Hour uint8
	/*Min Min reported by Gps  */
	Min uint8
	/*Sec Sec reported by Gps   */
	Sec uint8
	/*Clockstat Clock Status. See table 47 page 211 OEMStar Manual   */
	Clockstat uint8
	/*Vissat Visible satellites reported by Gps   */
	Vissat uint8
	/*Usesat Used satellites in Solution   */
	Usesat uint8
	/*Gppgl GPS+GLONASS satellites in Solution   */
	Gppgl uint8
	/*Sigusedmask GPS and GLONASS usage mask (bit 0 GPS_used? bit_4 GLONASS_used?) */
	Sigusedmask uint8
	/*PeRCentused Percent used GPS */
	PeRCentused uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

GPSDateTime Pilot console PWM messges.

func (*GPSDateTime) GetDialect

func (m *GPSDateTime) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*GPSDateTime) GetID

func (m *GPSDateTime) GetID() uint32

GetID gets the ID of the Message

func (*GPSDateTime) GetMessageName

func (m *GPSDateTime) GetMessageName() string

GetMessageName gets the name of the Message

func (*GPSDateTime) GetVersion

func (m *GPSDateTime) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*GPSDateTime) HasExtensionFields

func (m *GPSDateTime) HasExtensionFields() bool

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

func (*GPSDateTime) Read

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

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

func (*GPSDateTime) String

func (m *GPSDateTime) String() string

func (*GPSDateTime) Write

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

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

type IsrLocation

type IsrLocation struct {
	/*Latitude ISR Latitude */
	Latitude float32
	/*Longitude ISR Longitude */
	Longitude float32
	/*Height ISR Height */
	Height float32
	/*Target The system reporting the action */
	Target uint8
	/*Option1 Option 1 */
	Option1 uint8
	/*Option2 Option 2 */
	Option2 uint8
	/*Option3 Option 3 */
	Option3 uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

IsrLocation Transmits the position of watch

func (*IsrLocation) GetDialect

func (m *IsrLocation) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*IsrLocation) GetID

func (m *IsrLocation) GetID() uint32

GetID gets the ID of the Message

func (*IsrLocation) GetMessageName

func (m *IsrLocation) GetMessageName() string

GetMessageName gets the name of the Message

func (*IsrLocation) GetVersion

func (m *IsrLocation) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*IsrLocation) HasExtensionFields

func (m *IsrLocation) HasExtensionFields() bool

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

func (*IsrLocation) Read

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

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

func (*IsrLocation) String

func (m *IsrLocation) String() string

func (*IsrLocation) Write

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

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

type MIDLvlCmds

type MIDLvlCmds struct {
	/*Hcommand Commanded altitude (MSL) */
	Hcommand float32
	/*Ucommand Commanded Airspeed */
	Ucommand float32
	/*RCommand Commanded Turnrate */
	RCommand float32
	/*Target The system setting the commands */
	Target uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

MIDLvlCmds Mid Level commands sent from the GS to the autopilot. These are only sent when being operated in mid-level commands mode from the ground.

func (*MIDLvlCmds) GetDialect

func (m *MIDLvlCmds) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*MIDLvlCmds) GetID

func (m *MIDLvlCmds) GetID() uint32

GetID gets the ID of the Message

func (*MIDLvlCmds) GetMessageName

func (m *MIDLvlCmds) GetMessageName() string

GetMessageName gets the name of the Message

func (*MIDLvlCmds) GetVersion

func (m *MIDLvlCmds) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*MIDLvlCmds) HasExtensionFields

func (m *MIDLvlCmds) HasExtensionFields() bool

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

func (*MIDLvlCmds) Read

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

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

func (*MIDLvlCmds) String

func (m *MIDLvlCmds) String() string

func (*MIDLvlCmds) Write

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

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

type NovatelDiag

type NovatelDiag struct {
	/*Receiverstatus Status Bitfield. See table 69 page 350 Novatel OEMstar Manual */
	Receiverstatus uint32
	/*Possolage Age of the position solution */
	Possolage float32
	/*Csfails Times the CRC has failed since boot */
	Csfails uint16
	/*Timestatus The Time Status. See Table 8 page 27 Novatel OEMStar Manual */
	Timestatus uint8
	/*Solstatus solution Status. See table 44 page 197 */
	Solstatus uint8
	/*Postype position type. See table 43 page 196 */
	Postype uint8
	/*Veltype velocity type. See table 43 page 196 */
	Veltype uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

NovatelDiag Transmits the diagnostics data from the Novatel OEMStar GPS

func (*NovatelDiag) GetDialect

func (m *NovatelDiag) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*NovatelDiag) GetID

func (m *NovatelDiag) GetID() uint32

GetID gets the ID of the Message

func (*NovatelDiag) GetMessageName

func (m *NovatelDiag) GetMessageName() string

GetMessageName gets the name of the Message

func (*NovatelDiag) GetVersion

func (m *NovatelDiag) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*NovatelDiag) HasExtensionFields

func (m *NovatelDiag) HasExtensionFields() bool

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

func (*NovatelDiag) Read

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

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

func (*NovatelDiag) String

func (m *NovatelDiag) String() string

func (*NovatelDiag) Write

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

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

type PtzStatus

type PtzStatus struct {
	/*Pan The Pan value in 10ths of degree */
	Pan int16
	/*Tilt The Tilt value in 10ths of degree */
	Tilt int16
	/*Zoom The actual Zoom Value */
	Zoom uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

PtzStatus Transmits the actual Pan, Tilt and Zoom values of the camera unit

func (*PtzStatus) GetDialect

func (m *PtzStatus) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*PtzStatus) GetID

func (m *PtzStatus) GetID() uint32

GetID gets the ID of the Message

func (*PtzStatus) GetMessageName

func (m *PtzStatus) GetMessageName() string

GetMessageName gets the name of the Message

func (*PtzStatus) GetVersion

func (m *PtzStatus) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*PtzStatus) HasExtensionFields

func (m *PtzStatus) HasExtensionFields() bool

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

func (*PtzStatus) Read

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

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

func (*PtzStatus) String

func (m *PtzStatus) String() string

func (*PtzStatus) Write

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

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

type SensorBias

type SensorBias struct {
	/*Axbias Accelerometer X bias */
	Axbias float32
	/*Aybias Accelerometer Y bias */
	Aybias float32
	/*Azbias Accelerometer Z bias */
	Azbias float32
	/*Gxbias Gyro X bias */
	Gxbias float32
	/*Gybias Gyro Y bias */
	Gybias float32
	/*Gzbias Gyro Z bias */
	Gzbias float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SensorBias Accelerometer and gyro biases.

func (*SensorBias) GetDialect

func (m *SensorBias) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SensorBias) GetID

func (m *SensorBias) GetID() uint32

GetID gets the ID of the Message

func (*SensorBias) GetMessageName

func (m *SensorBias) GetMessageName() string

GetMessageName gets the name of the Message

func (*SensorBias) GetVersion

func (m *SensorBias) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SensorBias) HasExtensionFields

func (m *SensorBias) HasExtensionFields() bool

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

func (*SensorBias) Read

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

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

func (*SensorBias) String

func (m *SensorBias) String() string

func (*SensorBias) Write

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

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

type SensorDiag

type SensorDiag struct {
	/*Float1 Float field 1 */
	Float1 float32
	/*Float2 Float field 2 */
	Float2 float32
	/*Int1 Int 16 field 1 */
	Int1 int16
	/*Char1 Int 8 field 1 */
	Char1 int8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SensorDiag Diagnostic data Sensor MCU

func (*SensorDiag) GetDialect

func (m *SensorDiag) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SensorDiag) GetID

func (m *SensorDiag) GetID() uint32

GetID gets the ID of the Message

func (*SensorDiag) GetMessageName

func (m *SensorDiag) GetMessageName() string

GetMessageName gets the name of the Message

func (*SensorDiag) GetVersion

func (m *SensorDiag) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SensorDiag) HasExtensionFields

func (m *SensorDiag) HasExtensionFields() bool

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

func (*SensorDiag) Read

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

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

func (*SensorDiag) String

func (m *SensorDiag) String() string

func (*SensorDiag) Write

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

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

type SlugsCameraOrder

type SlugsCameraOrder struct {
	/*Target The system reporting the action */
	Target uint8
	/*Pan Order the mount to pan: -1 left, 0 No pan motion, +1 right */
	Pan int8
	/*Tilt Order the mount to tilt: -1 down, 0 No tilt motion, +1 up */
	Tilt int8
	/*Zoom Order the zoom values 0 to 10 */
	Zoom int8
	/*Movehome Orders the camera mount to move home. The other fields are ignored when this field is set. 1: move home, 0 ignored */
	Movehome int8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SlugsCameraOrder Orders generated to the SLUGS camera mount.

func (*SlugsCameraOrder) GetDialect

func (m *SlugsCameraOrder) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SlugsCameraOrder) GetID

func (m *SlugsCameraOrder) GetID() uint32

GetID gets the ID of the Message

func (*SlugsCameraOrder) GetMessageName

func (m *SlugsCameraOrder) GetMessageName() string

GetMessageName gets the name of the Message

func (*SlugsCameraOrder) GetVersion

func (m *SlugsCameraOrder) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SlugsCameraOrder) HasExtensionFields

func (m *SlugsCameraOrder) HasExtensionFields() bool

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

func (*SlugsCameraOrder) Read

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

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

func (*SlugsCameraOrder) String

func (m *SlugsCameraOrder) String() string

func (*SlugsCameraOrder) Write

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

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

type SlugsConfigurationCamera

type SlugsConfigurationCamera struct {
	/*Target The system setting the commands */
	Target uint8
	/*IDorder ID 0: brightness 1: aperture 2: iris 3: ICR 4: backlight */
	IDorder uint8
	/*Order  1: up/on 2: down/off 3: auto/reset/no action */
	Order uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SlugsConfigurationCamera Control for camara.

func (*SlugsConfigurationCamera) GetDialect

func (m *SlugsConfigurationCamera) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SlugsConfigurationCamera) GetID

func (m *SlugsConfigurationCamera) GetID() uint32

GetID gets the ID of the Message

func (*SlugsConfigurationCamera) GetMessageName

func (m *SlugsConfigurationCamera) GetMessageName() string

GetMessageName gets the name of the Message

func (*SlugsConfigurationCamera) GetVersion

func (m *SlugsConfigurationCamera) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SlugsConfigurationCamera) HasExtensionFields

func (m *SlugsConfigurationCamera) HasExtensionFields() bool

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

func (*SlugsConfigurationCamera) Read

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

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

func (*SlugsConfigurationCamera) String

func (m *SlugsConfigurationCamera) String() string

func (*SlugsConfigurationCamera) Write

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

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

type SlugsMobileLocation

type SlugsMobileLocation struct {
	/*Latitude Mobile Latitude */
	Latitude float32
	/*Longitude Mobile Longitude */
	Longitude float32
	/*Target The system reporting the action */
	Target uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SlugsMobileLocation Transmits the last known position of the mobile GS to the UAV. Very relevant when Track Mobile is enabled

func (*SlugsMobileLocation) GetDialect

func (m *SlugsMobileLocation) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SlugsMobileLocation) GetID

func (m *SlugsMobileLocation) GetID() uint32

GetID gets the ID of the Message

func (*SlugsMobileLocation) GetMessageName

func (m *SlugsMobileLocation) GetMessageName() string

GetMessageName gets the name of the Message

func (*SlugsMobileLocation) GetVersion

func (m *SlugsMobileLocation) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SlugsMobileLocation) HasExtensionFields

func (m *SlugsMobileLocation) HasExtensionFields() bool

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

func (*SlugsMobileLocation) Read

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

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

func (*SlugsMobileLocation) String

func (m *SlugsMobileLocation) String() string

func (*SlugsMobileLocation) Write

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

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

type SlugsNAVigation

type SlugsNAVigation struct {
	/*UM Measured Airspeed prior to the nav filter */
	UM float32
	/*PhiC Commanded Roll */
	PhiC float32
	/*ThetaC Commanded Pitch */
	ThetaC float32
	/*PsIDotC Commanded Turn rate */
	PsIDotC float32
	/*AyBody Y component of the body acceleration */
	AyBody float32
	/*Totaldist Total Distance to Run on this leg of Navigation */
	Totaldist float32
	/*Dist2Go Remaining distance to Run on this leg of Navigation */
	Dist2Go float32
	/*HC Commanded altitude (MSL) */
	HC uint16
	/*Fromwp Origin WP */
	Fromwp uint8
	/*Towp Destination WP */
	Towp uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SlugsNAVigation Data used in the navigation algorithm.

func (*SlugsNAVigation) GetDialect

func (m *SlugsNAVigation) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SlugsNAVigation) GetID

func (m *SlugsNAVigation) GetID() uint32

GetID gets the ID of the Message

func (*SlugsNAVigation) GetMessageName

func (m *SlugsNAVigation) GetMessageName() string

GetMessageName gets the name of the Message

func (*SlugsNAVigation) GetVersion

func (m *SlugsNAVigation) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SlugsNAVigation) HasExtensionFields

func (m *SlugsNAVigation) HasExtensionFields() bool

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

func (*SlugsNAVigation) Read

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

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

func (*SlugsNAVigation) String

func (m *SlugsNAVigation) String() string

func (*SlugsNAVigation) Write

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

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

type StatusGPS

type StatusGPS struct {
	/*Magvar Magnetic variation */
	Magvar float32
	/*Csfails Number of times checksum has failed */
	Csfails uint16
	/*GPSquality The quality indicator, 0=fix not available or invalid, 1=GPS fix, 2=C/A differential GPS, 6=Dead reckoning mode, 7=Manual input mode (fixed position), 8=Simulator mode, 9= WAAS a */
	GPSquality uint8
	/*Msgstype  Indicates if GN, GL or GP messages are being received */
	Msgstype uint8
	/*Posstatus  A = data valid, V = data invalid */
	Posstatus uint8
	/*Magdir  Magnetic variation direction E/W. Easterly variation (E) subtracts from True course and Westerly variation (W) adds to True course */
	Magdir int8
	/*Modeind  Positioning system mode indicator. A - Autonomous;D-Differential; E-Estimated (dead reckoning) mode;M-Manual input; N-Data not valid */
	Modeind uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

StatusGPS This contains the status of the GPS readings

func (*StatusGPS) GetDialect

func (m *StatusGPS) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*StatusGPS) GetID

func (m *StatusGPS) GetID() uint32

GetID gets the ID of the Message

func (*StatusGPS) GetMessageName

func (m *StatusGPS) GetMessageName() string

GetMessageName gets the name of the Message

func (*StatusGPS) GetVersion

func (m *StatusGPS) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*StatusGPS) HasExtensionFields

func (m *StatusGPS) HasExtensionFields() bool

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

func (*StatusGPS) Read

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

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

func (*StatusGPS) String

func (m *StatusGPS) String() string

func (*StatusGPS) Write

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

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

type UavStatus

type UavStatus struct {
	/*Latitude Latitude UAV */
	Latitude float32
	/*Longitude Longitude UAV */
	Longitude float32
	/*Altitude Altitude UAV */
	Altitude float32
	/*Speed Speed UAV */
	Speed float32
	/*Course Course UAV */
	Course float32
	/*Target The ID system reporting the action */
	Target uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

UavStatus Transmits the actual status values UAV in flight

func (*UavStatus) GetDialect

func (m *UavStatus) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*UavStatus) GetID

func (m *UavStatus) GetID() uint32

GetID gets the ID of the Message

func (*UavStatus) GetMessageName

func (m *UavStatus) GetMessageName() string

GetMessageName gets the name of the Message

func (*UavStatus) GetVersion

func (m *UavStatus) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*UavStatus) HasExtensionFields

func (m *UavStatus) HasExtensionFields() bool

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

func (*UavStatus) Read

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

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

func (*UavStatus) String

func (m *UavStatus) String() string

func (*UavStatus) Write

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

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

type VoltSensor

type VoltSensor struct {
	/*Voltage Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V  */
	Voltage uint16
	/*Reading2 Depends on the value of r2Type (0) Current consumption in uS of PWM, 20 uS = 90Amp (1) Distance in cm (2) Distance in cm (3) Absolute value */
	Reading2 uint16
	/*R2Type It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM */
	R2Type uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

VoltSensor Transmits the readings from the voltage and current sensors

func (*VoltSensor) GetDialect

func (m *VoltSensor) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*VoltSensor) GetID

func (m *VoltSensor) GetID() uint32

GetID gets the ID of the Message

func (*VoltSensor) GetMessageName

func (m *VoltSensor) GetMessageName() string

GetMessageName gets the name of the Message

func (*VoltSensor) GetVersion

func (m *VoltSensor) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*VoltSensor) HasExtensionFields

func (m *VoltSensor) HasExtensionFields() bool

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

func (*VoltSensor) Read

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

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

func (*VoltSensor) String

func (m *VoltSensor) String() string

func (*VoltSensor) Write

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