asluav

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
	/*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
	/*MavCmdResetMppt - Mission command to reset Maximum Power Point Tracker (MPPT) */
	MavCmdResetMppt = 40001
	/*MavCmdPayloadControl - Mission command to perform a power cycle on payload */
	MavCmdPayloadControl = 40002
	/*MavCmdEnumEnd -  */
	MavCmdEnumEnd = 40003
)

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 (
	/*GsmLinkTypeNone - no service */
	GsmLinkTypeNone = 0
	/*GsmLinkTypeUnknown - link type unknown */
	GsmLinkTypeUnknown = 1
	/*GsmLinkType2G - 2G (GSM/GRPS/EDGE) link */
	GsmLinkType2G = 2
	/*GsmLinkType3G - 3G link (WCDMA/HSDPA/HSPA)  */
	GsmLinkType3G = 3
	/*GsmLinkType4G - 4G link (LTE) */
	GsmLinkType4G = 4
	/*GsmLinkTypeEnumEnd -  */
	GsmLinkTypeEnumEnd = 5
)

GSM_LINK_TYPE -

View Source
const (
	/*GsmModemTypeUnknown - not specified */
	GsmModemTypeUnknown = 0
	/*GsmModemTypeHuaweiE3372 - HUAWEI LTE USB Stick E3372 */
	GsmModemTypeHuaweiE3372 = 1
	/*GsmModemTypeEnumEnd -  */
	GsmModemTypeEnumEnd = 2
)

GSM_MODEM_TYPE -

Variables

View Source
var ASLUAVParsers = map[uint32]mavlink2.FrameParser{
	78: mavlink2.FrameParser(func(frame mavlink2.Frame) (message mavlink2.Message, err error) {
		message = &CommandIntStamped{}

		err = message.Read(frame)

		return
	}),
	79: mavlink2.FrameParser(func(frame mavlink2.Frame) (message mavlink2.Message, err error) {
		message = &CommandLongStamped{}

		err = message.Read(frame)

		return
	}),
	201: mavlink2.FrameParser(func(frame mavlink2.Frame) (message mavlink2.Message, err error) {
		message = &SensPower{}

		err = message.Read(frame)

		return
	}),
	202: mavlink2.FrameParser(func(frame mavlink2.Frame) (message mavlink2.Message, err error) {
		message = &SensMppt{}

		err = message.Read(frame)

		return
	}),
	203: mavlink2.FrameParser(func(frame mavlink2.Frame) (message mavlink2.Message, err error) {
		message = &AslctrlData{}

		err = message.Read(frame)

		return
	}),
	204: mavlink2.FrameParser(func(frame mavlink2.Frame) (message mavlink2.Message, err error) {
		message = &AslctrlDebug{}

		err = message.Read(frame)

		return
	}),
	205: mavlink2.FrameParser(func(frame mavlink2.Frame) (message mavlink2.Message, err error) {
		message = &AsluavStatus{}

		err = message.Read(frame)

		return
	}),
	206: mavlink2.FrameParser(func(frame mavlink2.Frame) (message mavlink2.Message, err error) {
		message = &EKFExt{}

		err = message.Read(frame)

		return
	}),
	207: mavlink2.FrameParser(func(frame mavlink2.Frame) (message mavlink2.Message, err error) {
		message = &AslObctrl{}

		err = message.Read(frame)

		return
	}),
	208: mavlink2.FrameParser(func(frame mavlink2.Frame) (message mavlink2.Message, err error) {
		message = &SensAtmos{}

		err = message.Read(frame)

		return
	}),
	209: mavlink2.FrameParser(func(frame mavlink2.Frame) (message mavlink2.Message, err error) {
		message = &SensBatmon{}

		err = message.Read(frame)

		return
	}),
	210: mavlink2.FrameParser(func(frame mavlink2.Frame) (message mavlink2.Message, err error) {
		message = &FwSoaringData{}

		err = message.Read(frame)

		return
	}),
	211: mavlink2.FrameParser(func(frame mavlink2.Frame) (message mavlink2.Message, err error) {
		message = &SensorpodStatus{}

		err = message.Read(frame)

		return
	}),
	212: mavlink2.FrameParser(func(frame mavlink2.Frame) (message mavlink2.Message, err error) {
		message = &SensPowerBoard{}

		err = message.Read(frame)

		return
	}),
	213: mavlink2.FrameParser(func(frame mavlink2.Frame) (message mavlink2.Message, err error) {
		message = &GsmLinkStatus{}

		err = message.Read(frame)

		return
	}),
}

Functions

This section is empty.

Types

type AslObctrl

type AslObctrl struct {
	/*Timestamp  Time since system start */
	Timestamp uint64
	/*Uelev  Elevator command [~] */
	Uelev float32
	/*Uthrot  Throttle command [~] */
	Uthrot float32
	/*Uthrot2  Throttle 2 command [~] */
	Uthrot2 float32
	/*Uaill  Left aileron command [~] */
	Uaill float32
	/*Uailr  Right aileron command [~] */
	Uailr float32
	/*Urud  Rudder command [~] */
	Urud float32
	/*ObctrlStatus  Off-board computer status */
	ObctrlStatus uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

AslObctrl Off-board controls/commands for ASLUAVs

func (*AslObctrl) GetDialect

func (m *AslObctrl) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*AslObctrl) GetID

func (m *AslObctrl) GetID() uint32

GetID gets the ID of the Message

func (*AslObctrl) GetMessageName

func (m *AslObctrl) GetMessageName() string

GetMessageName gets the name of the Message

func (*AslObctrl) GetVersion

func (m *AslObctrl) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*AslObctrl) HasExtensionFields

func (m *AslObctrl) HasExtensionFields() bool

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

func (*AslObctrl) Read

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

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

func (*AslObctrl) String

func (m *AslObctrl) String() string

func (*AslObctrl) Write

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

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

type AslctrlData

type AslctrlData struct {
	/*Timestamp  Timestamp */
	Timestamp uint64
	/*H  See sourcecode for a description of these values...  */
	H float32
	/*Href   */
	Href float32
	/*HrefT   */
	HrefT float32
	/*Pitchangle Pitch angle */
	Pitchangle float32
	/*Pitchangleref Pitch angle reference */
	Pitchangleref float32
	/*Q   */
	Q float32
	/*Qref   */
	Qref float32
	/*Uelev   */
	Uelev float32
	/*Uthrot   */
	Uthrot float32
	/*Uthrot2   */
	Uthrot2 float32
	/*Nz   */
	Nz float32
	/*Airspeedref Airspeed reference */
	Airspeedref float32
	/*Yawangle Yaw angle */
	Yawangle float32
	/*Yawangleref Yaw angle reference */
	Yawangleref float32
	/*Rollangle Roll angle */
	Rollangle float32
	/*Rollangleref Roll angle reference */
	Rollangleref float32
	/*P   */
	P float32
	/*Pref   */
	Pref float32
	/*R   */
	R float32
	/*Rref   */
	Rref float32
	/*Uail   */
	Uail float32
	/*Urud   */
	Urud float32
	/*AslctrlMode  ASLCTRL control-mode (manual, stabilized, auto, etc...) */
	AslctrlMode uint8
	/*Spoilersengaged   */
	Spoilersengaged uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

AslctrlData ASL-fixed-wing controller data

func (*AslctrlData) GetDialect

func (m *AslctrlData) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*AslctrlData) GetID

func (m *AslctrlData) GetID() uint32

GetID gets the ID of the Message

func (*AslctrlData) GetMessageName

func (m *AslctrlData) GetMessageName() string

GetMessageName gets the name of the Message

func (*AslctrlData) GetVersion

func (m *AslctrlData) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*AslctrlData) HasExtensionFields

func (m *AslctrlData) HasExtensionFields() bool

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

func (*AslctrlData) Read

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

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

func (*AslctrlData) String

func (m *AslctrlData) String() string

func (*AslctrlData) Write

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

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

type AslctrlDebug

type AslctrlDebug struct {
	/*I321  Debug data */
	I321 uint32
	/*F1  Debug data  */
	F1 float32
	/*F2  Debug data */
	F2 float32
	/*F3  Debug data */
	F3 float32
	/*F4  Debug data */
	F4 float32
	/*F5  Debug data */
	F5 float32
	/*F6  Debug data */
	F6 float32
	/*F7  Debug data */
	F7 float32
	/*F8  Debug data */
	F8 float32
	/*I81  Debug data */
	I81 uint8
	/*I82  Debug data */
	I82 uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

AslctrlDebug ASL-fixed-wing controller debug data

func (*AslctrlDebug) GetDialect

func (m *AslctrlDebug) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*AslctrlDebug) GetID

func (m *AslctrlDebug) GetID() uint32

GetID gets the ID of the Message

func (*AslctrlDebug) GetMessageName

func (m *AslctrlDebug) GetMessageName() string

GetMessageName gets the name of the Message

func (*AslctrlDebug) GetVersion

func (m *AslctrlDebug) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*AslctrlDebug) HasExtensionFields

func (m *AslctrlDebug) HasExtensionFields() bool

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

func (*AslctrlDebug) Read

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

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

func (*AslctrlDebug) String

func (m *AslctrlDebug) String() string

func (*AslctrlDebug) Write

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

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

type AsluavStatus

type AsluavStatus struct {
	/*MotorRpm  Motor RPM  */
	MotorRpm float32
	/*LedStatus  Status of the position-indicator LEDs */
	LedStatus uint8
	/*SatcomStatus  Status of the IRIDIUM satellite communication system */
	SatcomStatus uint8
	/*ServoStatus  Status vector for up to 8 servos */
	ServoStatus [8]uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

AsluavStatus Extended state information for ASLUAVs

func (*AsluavStatus) GetDialect

func (m *AsluavStatus) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*AsluavStatus) GetID

func (m *AsluavStatus) GetID() uint32

GetID gets the ID of the Message

func (*AsluavStatus) GetMessageName

func (m *AsluavStatus) GetMessageName() string

GetMessageName gets the name of the Message

func (*AsluavStatus) GetVersion

func (m *AsluavStatus) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*AsluavStatus) HasExtensionFields

func (m *AsluavStatus) HasExtensionFields() bool

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

func (*AsluavStatus) Read

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

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

func (*AsluavStatus) String

func (m *AsluavStatus) String() string

func (*AsluavStatus) Write

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

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

type CommandIntStamped

type CommandIntStamped struct {
	/*VehicleTimestamp Microseconds elapsed since vehicle boot */
	VehicleTimestamp uint64
	/*UtcTime UTC time, seconds elapsed since 01.01.1970 */
	UtcTime uint32
	/*Param1 PARAM1, see MAV_CMD enum */
	Param1 float32
	/*Param2 PARAM2, see MAV_CMD enum */
	Param2 float32
	/*Param3 PARAM3, see MAV_CMD enum */
	Param3 float32
	/*Param4 PARAM4, see MAV_CMD enum */
	Param4 float32
	/*X PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7 */
	X int32
	/*Y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7 */
	Y int32
	/*Z PARAM7 / z position: global: altitude in meters (MSL, WGS84, AGL or relative to home - depending on frame). */
	Z float32
	/*Command The scheduled action for the mission item, as defined by MAV_CMD enum */
	Command uint16
	/*TargetSystem System ID */
	TargetSystem uint8
	/*TargetComponent Component ID */
	TargetComponent uint8
	/*Frame The coordinate system of the COMMAND, as defined by MAV_FRAME enum */
	Frame uint8
	/*Current false:0, true:1 */
	Current uint8
	/*Autocontinue autocontinue to next wp */
	Autocontinue uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

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

func (*CommandIntStamped) GetDialect

func (m *CommandIntStamped) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*CommandIntStamped) GetID

func (m *CommandIntStamped) GetID() uint32

GetID gets the ID of the Message

func (*CommandIntStamped) GetMessageName

func (m *CommandIntStamped) GetMessageName() string

GetMessageName gets the name of the Message

func (*CommandIntStamped) GetVersion

func (m *CommandIntStamped) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*CommandIntStamped) HasExtensionFields

func (m *CommandIntStamped) HasExtensionFields() bool

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

func (*CommandIntStamped) Read

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

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

func (*CommandIntStamped) String

func (m *CommandIntStamped) String() string

func (*CommandIntStamped) Write

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

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

type CommandLongStamped

type CommandLongStamped struct {
	/*VehicleTimestamp Microseconds elapsed since vehicle boot */
	VehicleTimestamp uint64
	/*UtcTime UTC time, seconds elapsed since 01.01.1970 */
	UtcTime uint32
	/*Param1 Parameter 1, as defined by MAV_CMD enum. */
	Param1 float32
	/*Param2 Parameter 2, as defined by MAV_CMD enum. */
	Param2 float32
	/*Param3 Parameter 3, as defined by MAV_CMD enum. */
	Param3 float32
	/*Param4 Parameter 4, as defined by MAV_CMD enum. */
	Param4 float32
	/*Param5 Parameter 5, as defined by MAV_CMD enum. */
	Param5 float32
	/*Param6 Parameter 6, as defined by MAV_CMD enum. */
	Param6 float32
	/*Param7 Parameter 7, as defined by MAV_CMD enum. */
	Param7 float32
	/*Command Command ID, as defined by MAV_CMD enum. */
	Command uint16
	/*TargetSystem System which should execute the command */
	TargetSystem uint8
	/*TargetComponent Component which should execute the command, 0 for all components */
	TargetComponent uint8
	/*Confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) */
	Confirmation uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

CommandLongStamped Send a command with up to seven parameters to the MAV and additional metadata

func (*CommandLongStamped) GetDialect

func (m *CommandLongStamped) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*CommandLongStamped) GetID

func (m *CommandLongStamped) GetID() uint32

GetID gets the ID of the Message

func (*CommandLongStamped) GetMessageName

func (m *CommandLongStamped) GetMessageName() string

GetMessageName gets the name of the Message

func (*CommandLongStamped) GetVersion

func (m *CommandLongStamped) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*CommandLongStamped) HasExtensionFields

func (m *CommandLongStamped) HasExtensionFields() bool

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

func (*CommandLongStamped) Read

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

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

func (*CommandLongStamped) String

func (m *CommandLongStamped) String() string

func (*CommandLongStamped) Write

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

type EKFExt struct {
	/*Timestamp  Time since system start */
	Timestamp uint64
	/*Windspeed  Magnitude of wind velocity (in lateral inertial plane) */
	Windspeed float32
	/*Winddir  Wind heading angle from North */
	Winddir float32
	/*Windz  Z (Down) component of inertial wind velocity */
	Windz float32
	/*Airspeed  Magnitude of air velocity */
	Airspeed float32
	/*Beta  Sideslip angle */
	Beta float32
	/*Alpha  Angle of attack */
	Alpha float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

EKFExt Extended EKF state estimates for ASLUAVs

func (*EKFExt) GetDialect

func (m *EKFExt) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*EKFExt) GetID

func (m *EKFExt) GetID() uint32

GetID gets the ID of the Message

func (*EKFExt) GetMessageName

func (m *EKFExt) GetMessageName() string

GetMessageName gets the name of the Message

func (*EKFExt) GetVersion

func (m *EKFExt) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*EKFExt) HasExtensionFields

func (m *EKFExt) HasExtensionFields() bool

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

func (*EKFExt) Read

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

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

func (*EKFExt) String

func (m *EKFExt) String() string

func (*EKFExt) Write

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

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

type FwSoaringData

type FwSoaringData struct {
	/*Timestamp Timestamp */
	Timestamp uint64
	/*Timestampmodechanged Timestamp since last mode change */
	Timestampmodechanged uint64
	/*Xw Thermal core updraft strength */
	Xw float32
	/*Xr Thermal radius */
	Xr float32
	/*Xlat Thermal center latitude */
	Xlat float32
	/*Xlon Thermal center longitude */
	Xlon float32
	/*Varw Variance W */
	Varw float32
	/*Varr Variance R */
	Varr float32
	/*Varlat Variance Lat */
	Varlat float32
	/*Varlon Variance Lon  */
	Varlon float32
	/*Loiterradius Suggested loiter radius */
	Loiterradius float32
	/*Loiterdirection Suggested loiter direction */
	Loiterdirection float32
	/*Disttosoarpoint Distance to soar point */
	Disttosoarpoint float32
	/*Vsinkexp Expected sink rate at current airspeed, roll and throttle */
	Vsinkexp float32
	/*Z1Localupdraftspeed Measurement / updraft speed at current/local airplane position */
	Z1Localupdraftspeed float32
	/*Z2Deltaroll Measurement / roll angle tracking error */
	Z2Deltaroll float32
	/*Z1Exp Expected measurement 1 */
	Z1Exp float32
	/*Z2Exp Expected measurement 2 */
	Z2Exp float32
	/*Thermalgsnorth Thermal drift (from estimator prediction step only) */
	Thermalgsnorth float32
	/*Thermalgseast Thermal drift (from estimator prediction step only) */
	Thermalgseast float32
	/*TseDot  Total specific energy change (filtered) */
	TseDot float32
	/*Debugvar1  Debug variable 1 */
	Debugvar1 float32
	/*Debugvar2  Debug variable 2 */
	Debugvar2 float32
	/*Controlmode Control Mode [-] */
	Controlmode uint8
	/*ValID Data valid [-] */
	ValID uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

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

func (*FwSoaringData) GetDialect

func (m *FwSoaringData) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*FwSoaringData) GetID

func (m *FwSoaringData) GetID() uint32

GetID gets the ID of the Message

func (*FwSoaringData) GetMessageName

func (m *FwSoaringData) GetMessageName() string

GetMessageName gets the name of the Message

func (*FwSoaringData) GetVersion

func (m *FwSoaringData) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*FwSoaringData) HasExtensionFields

func (m *FwSoaringData) HasExtensionFields() bool

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

func (*FwSoaringData) Read

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

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

func (*FwSoaringData) String

func (m *FwSoaringData) String() string

func (*FwSoaringData) Write

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

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

type GsmLinkStatus

type GsmLinkStatus struct {
	/*Timestamp Timestamp (of OBC) */
	Timestamp uint64
	/*GsmModemType GSM modem used */
	GsmModemType uint8
	/*GsmLinkType GSM link type */
	GsmLinkType uint8
	/*RSSI RSSI as reported by modem (unconverted) */
	RSSI uint8
	/*RsrpRscp RSRP (LTE) or RSCP (WCDMA) as reported by modem (unconverted) */
	RsrpRscp uint8
	/*SinrEcio SINR (LTE) or ECIO (WCDMA) as reported by modem (unconverted) */
	SinrEcio uint8
	/*Rsrq RSRQ (LTE only) as reported by modem (unconverted) */
	Rsrq uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

GsmLinkStatus Status of GSM modem (connected to onboard computer)

func (*GsmLinkStatus) GetDialect

func (m *GsmLinkStatus) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*GsmLinkStatus) GetID

func (m *GsmLinkStatus) GetID() uint32

GetID gets the ID of the Message

func (*GsmLinkStatus) GetMessageName

func (m *GsmLinkStatus) GetMessageName() string

GetMessageName gets the name of the Message

func (*GsmLinkStatus) GetVersion

func (m *GsmLinkStatus) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*GsmLinkStatus) HasExtensionFields

func (m *GsmLinkStatus) HasExtensionFields() bool

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

func (*GsmLinkStatus) Read

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

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

func (*GsmLinkStatus) String

func (m *GsmLinkStatus) String() string

func (*GsmLinkStatus) Write

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

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

type SatcomLinkStatus

type SatcomLinkStatus struct {
	/*Timestamp Timestamp */
	Timestamp uint64
	/*LastHeartbeat Timestamp of the last successful sbd session */
	LastHeartbeat uint64
	/*FailedSessions Number of failed sessions */
	FailedSessions uint16
	/*SuccessfulSessions Number of successful sessions */
	SuccessfulSessions uint16
	/*SignalQuality Signal quality */
	SignalQuality uint8
	/*RingPending Ring call pending */
	RingPending uint8
	/*TxSessionPending Transmission session pending */
	TxSessionPending uint8
	/*RxSessionPending Receiving session pending */
	RxSessionPending uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SatcomLinkStatus Status of the SatCom link

func (*SatcomLinkStatus) GetDialect

func (m *SatcomLinkStatus) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SatcomLinkStatus) GetID

func (m *SatcomLinkStatus) GetID() uint32

GetID gets the ID of the Message

func (*SatcomLinkStatus) GetMessageName

func (m *SatcomLinkStatus) GetMessageName() string

GetMessageName gets the name of the Message

func (*SatcomLinkStatus) GetVersion

func (m *SatcomLinkStatus) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SatcomLinkStatus) HasExtensionFields

func (m *SatcomLinkStatus) HasExtensionFields() bool

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

func (*SatcomLinkStatus) Read

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

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

func (*SatcomLinkStatus) String

func (m *SatcomLinkStatus) String() string

func (*SatcomLinkStatus) Write

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

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

type SensAtmos

type SensAtmos struct {
	/*Timestamp Time since system boot */
	Timestamp uint64
	/*Tempambient  Ambient temperature */
	Tempambient float32
	/*HumIDity  Relative humidity */
	HumIDity float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SensAtmos Atmospheric sensors (temperature, humidity, ...)

func (*SensAtmos) GetDialect

func (m *SensAtmos) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SensAtmos) GetID

func (m *SensAtmos) GetID() uint32

GetID gets the ID of the Message

func (*SensAtmos) GetMessageName

func (m *SensAtmos) GetMessageName() string

GetMessageName gets the name of the Message

func (*SensAtmos) GetVersion

func (m *SensAtmos) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SensAtmos) HasExtensionFields

func (m *SensAtmos) HasExtensionFields() bool

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

func (*SensAtmos) Read

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

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

func (*SensAtmos) String

func (m *SensAtmos) String() string

func (*SensAtmos) Write

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

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

type SensBatmon

type SensBatmon struct {
	/*BatmonTimestamp Time since system start */
	BatmonTimestamp uint64
	/*Temperature Battery pack temperature */
	Temperature float32
	/*Safetystatus Battery monitor safetystatus report bits in Hex */
	Safetystatus uint32
	/*Operationstatus Battery monitor operation status report bits in Hex */
	Operationstatus uint32
	/*Voltage Battery pack voltage */
	Voltage uint16
	/*Current Battery pack current */
	Current int16
	/*Batterystatus Battery monitor status report bits in Hex */
	Batterystatus uint16
	/*Serialnumber Battery monitor serial number in Hex */
	Serialnumber uint16
	/*Cellvoltage1 Battery pack cell 1 voltage */
	Cellvoltage1 uint16
	/*Cellvoltage2 Battery pack cell 2 voltage */
	Cellvoltage2 uint16
	/*Cellvoltage3 Battery pack cell 3 voltage */
	Cellvoltage3 uint16
	/*Cellvoltage4 Battery pack cell 4 voltage */
	Cellvoltage4 uint16
	/*Cellvoltage5 Battery pack cell 5 voltage */
	Cellvoltage5 uint16
	/*Cellvoltage6 Battery pack cell 6 voltage */
	Cellvoltage6 uint16
	/*Soc Battery pack state-of-charge */
	Soc uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SensBatmon Battery pack monitoring data for Li-Ion batteries

func (*SensBatmon) GetDialect

func (m *SensBatmon) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SensBatmon) GetID

func (m *SensBatmon) GetID() uint32

GetID gets the ID of the Message

func (*SensBatmon) GetMessageName

func (m *SensBatmon) GetMessageName() string

GetMessageName gets the name of the Message

func (*SensBatmon) GetVersion

func (m *SensBatmon) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SensBatmon) HasExtensionFields

func (m *SensBatmon) HasExtensionFields() bool

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

func (*SensBatmon) Read

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

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

func (*SensBatmon) String

func (m *SensBatmon) String() string

func (*SensBatmon) Write

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

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

type SensMppt

type SensMppt struct {
	/*MpptTimestamp  MPPT last timestamp  */
	MpptTimestamp uint64
	/*Mppt1Volt  MPPT1 voltage  */
	Mppt1Volt float32
	/*Mppt1Amp  MPPT1 current  */
	Mppt1Amp float32
	/*Mppt2Volt  MPPT2 voltage  */
	Mppt2Volt float32
	/*Mppt2Amp  MPPT2 current  */
	Mppt2Amp float32
	/*Mppt3Volt MPPT3 voltage  */
	Mppt3Volt float32
	/*Mppt3Amp  MPPT3 current  */
	Mppt3Amp float32
	/*Mppt1Pwm  MPPT1 pwm  */
	Mppt1Pwm uint16
	/*Mppt2Pwm  MPPT2 pwm  */
	Mppt2Pwm uint16
	/*Mppt3Pwm  MPPT3 pwm  */
	Mppt3Pwm uint16
	/*Mppt1Status  MPPT1 status  */
	Mppt1Status uint8
	/*Mppt2Status  MPPT2 status  */
	Mppt2Status uint8
	/*Mppt3Status  MPPT3 status  */
	Mppt3Status uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

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

func (*SensMppt) GetDialect

func (m *SensMppt) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SensMppt) GetID

func (m *SensMppt) GetID() uint32

GetID gets the ID of the Message

func (*SensMppt) GetMessageName

func (m *SensMppt) GetMessageName() string

GetMessageName gets the name of the Message

func (*SensMppt) GetVersion

func (m *SensMppt) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SensMppt) HasExtensionFields

func (m *SensMppt) HasExtensionFields() bool

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

func (*SensMppt) Read

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

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

func (*SensMppt) String

func (m *SensMppt) String() string

func (*SensMppt) Write

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

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

type SensPower

type SensPower struct {
	/*Adc121VspbVolt  Power board voltage sensor reading */
	Adc121VspbVolt float32
	/*Adc121CspbAmp  Power board current sensor reading */
	Adc121CspbAmp float32
	/*Adc121Cs1Amp  Board current sensor 1 reading */
	Adc121Cs1Amp float32
	/*Adc121Cs2Amp  Board current sensor 2 reading */
	Adc121Cs2Amp float32
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SensPower Voltage and current sensor data

func (*SensPower) GetDialect

func (m *SensPower) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SensPower) GetID

func (m *SensPower) GetID() uint32

GetID gets the ID of the Message

func (*SensPower) GetMessageName

func (m *SensPower) GetMessageName() string

GetMessageName gets the name of the Message

func (*SensPower) GetVersion

func (m *SensPower) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SensPower) HasExtensionFields

func (m *SensPower) HasExtensionFields() bool

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

func (*SensPower) Read

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

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

func (*SensPower) String

func (m *SensPower) String() string

func (*SensPower) Write

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

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

type SensPowerBoard

type SensPowerBoard struct {
	/*Timestamp Timestamp */
	Timestamp uint64
	/*PwrBrdSystemVolt Power board system voltage */
	PwrBrdSystemVolt float32
	/*PwrBrdServoVolt Power board servo voltage */
	PwrBrdServoVolt float32
	/*PwrBrdDigitalVolt Power board digital voltage */
	PwrBrdDigitalVolt float32
	/*PwrBrdMotLAmp Power board left motor current sensor */
	PwrBrdMotLAmp float32
	/*PwrBrdMotRAmp Power board right motor current sensor */
	PwrBrdMotRAmp float32
	/*PwrBrdAnalogAmp Power board analog current sensor */
	PwrBrdAnalogAmp float32
	/*PwrBrdDigitalAmp Power board digital current sensor */
	PwrBrdDigitalAmp float32
	/*PwrBrdExtAmp Power board extension current sensor */
	PwrBrdExtAmp float32
	/*PwrBrdAuxAmp Power board aux current sensor */
	PwrBrdAuxAmp float32
	/*PwrBrdStatus Power board status register */
	PwrBrdStatus uint8
	/*PwrBrdLedStatus Power board leds status */
	PwrBrdLedStatus uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SensPowerBoard Monitoring of power board status

func (*SensPowerBoard) GetDialect

func (m *SensPowerBoard) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SensPowerBoard) GetID

func (m *SensPowerBoard) GetID() uint32

GetID gets the ID of the Message

func (*SensPowerBoard) GetMessageName

func (m *SensPowerBoard) GetMessageName() string

GetMessageName gets the name of the Message

func (*SensPowerBoard) GetVersion

func (m *SensPowerBoard) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SensPowerBoard) HasExtensionFields

func (m *SensPowerBoard) HasExtensionFields() bool

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

func (*SensPowerBoard) Read

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

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

func (*SensPowerBoard) String

func (m *SensPowerBoard) String() string

func (*SensPowerBoard) Write

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

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

type SensorpodStatus

type SensorpodStatus struct {
	/*Timestamp Timestamp in linuxtime (since 1.1.1970) */
	Timestamp uint64
	/*FreeSpace Free space available in recordings directory in [Gb] * 1e2 */
	FreeSpace uint16
	/*VisensorRate1 Rate of ROS topic 1 */
	VisensorRate1 uint8
	/*VisensorRate2 Rate of ROS topic 2 */
	VisensorRate2 uint8
	/*VisensorRate3 Rate of ROS topic 3 */
	VisensorRate3 uint8
	/*VisensorRate4 Rate of ROS topic 4 */
	VisensorRate4 uint8
	/*RecordingNodesCount Number of recording nodes */
	RecordingNodesCount uint8
	/*CpuTemp Temperature of sensorpod CPU in */
	CpuTemp uint8
	/*HasExtensionFieldValues indicates if this message has any extensions and  */
	HasExtensionFieldValues bool
}

SensorpodStatus Monitoring of sensorpod status

func (*SensorpodStatus) GetDialect

func (m *SensorpodStatus) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*SensorpodStatus) GetID

func (m *SensorpodStatus) GetID() uint32

GetID gets the ID of the Message

func (*SensorpodStatus) GetMessageName

func (m *SensorpodStatus) GetMessageName() string

GetMessageName gets the name of the Message

func (*SensorpodStatus) GetVersion

func (m *SensorpodStatus) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*SensorpodStatus) HasExtensionFields

func (m *SensorpodStatus) HasExtensionFields() bool

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

func (*SensorpodStatus) Read

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

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

func (*SensorpodStatus) String

func (m *SensorpodStatus) String() string

func (*SensorpodStatus) Write

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