all

package
v1.5.2 Latest Latest
Warning

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

Go to latest
Published: Mar 2, 2021 License: Apache-2.0 Imports: 11 Imported by: 0

Documentation

Index

Constants

View Source
const (
	SENSOR_OFFSETS_FIELD_MAG_DECLINATION = "SensorOffsets.MagDeclination"
	SENSOR_OFFSETS_FIELD_RAW_PRESS       = "SensorOffsets.RawPress"
	SENSOR_OFFSETS_FIELD_RAW_TEMP        = "SensorOffsets.RawTemp"
	SENSOR_OFFSETS_FIELD_GYRO_CAL_X      = "SensorOffsets.GyroCalX"
	SENSOR_OFFSETS_FIELD_GYRO_CAL_Y      = "SensorOffsets.GyroCalY"
	SENSOR_OFFSETS_FIELD_GYRO_CAL_Z      = "SensorOffsets.GyroCalZ"
	SENSOR_OFFSETS_FIELD_ACCEL_CAL_X     = "SensorOffsets.AccelCalX"
	SENSOR_OFFSETS_FIELD_ACCEL_CAL_Y     = "SensorOffsets.AccelCalY"
	SENSOR_OFFSETS_FIELD_ACCEL_CAL_Z     = "SensorOffsets.AccelCalZ"
	SENSOR_OFFSETS_FIELD_MAG_OFS_X       = "SensorOffsets.MagOfsX"
	SENSOR_OFFSETS_FIELD_MAG_OFS_Y       = "SensorOffsets.MagOfsY"
	SENSOR_OFFSETS_FIELD_MAG_OFS_Z       = "SensorOffsets.MagOfsZ"
)
View Source
const (
	SET_MAG_OFFSETS_FIELD_MAG_OFS_X        = "SetMagOffsets.MagOfsX"
	SET_MAG_OFFSETS_FIELD_MAG_OFS_Y        = "SetMagOffsets.MagOfsY"
	SET_MAG_OFFSETS_FIELD_MAG_OFS_Z        = "SetMagOffsets.MagOfsZ"
	SET_MAG_OFFSETS_FIELD_TARGET_SYSTEM    = "SetMagOffsets.TargetSystem"
	SET_MAG_OFFSETS_FIELD_TARGET_COMPONENT = "SetMagOffsets.TargetComponent"
)
View Source
const (
	MEMINFO_FIELD_BRKVAL  = "Meminfo.Brkval"
	MEMINFO_FIELD_FREEMEM = "Meminfo.Freemem"
)
View Source
const (
	AP_ADC_FIELD_ADC1 = "ApAdc.Adc1"
	AP_ADC_FIELD_ADC2 = "ApAdc.Adc2"
	AP_ADC_FIELD_ADC3 = "ApAdc.Adc3"
	AP_ADC_FIELD_ADC4 = "ApAdc.Adc4"
	AP_ADC_FIELD_ADC5 = "ApAdc.Adc5"
	AP_ADC_FIELD_ADC6 = "ApAdc.Adc6"
)
View Source
const (
	DIGICAM_CONFIGURE_FIELD_EXTRA_VALUE      = "DigicamConfigure.ExtraValue"
	DIGICAM_CONFIGURE_FIELD_SHUTTER_SPEED    = "DigicamConfigure.ShutterSpeed"
	DIGICAM_CONFIGURE_FIELD_TARGET_SYSTEM    = "DigicamConfigure.TargetSystem"
	DIGICAM_CONFIGURE_FIELD_TARGET_COMPONENT = "DigicamConfigure.TargetComponent"
	DIGICAM_CONFIGURE_FIELD_MODE             = "DigicamConfigure.Mode"
	DIGICAM_CONFIGURE_FIELD_APERTURE         = "DigicamConfigure.Aperture"
	DIGICAM_CONFIGURE_FIELD_ISO              = "DigicamConfigure.Iso"
	DIGICAM_CONFIGURE_FIELD_EXPOSURE_TYPE    = "DigicamConfigure.ExposureType"
	DIGICAM_CONFIGURE_FIELD_COMMAND_ID       = "DigicamConfigure.CommandID"
	DIGICAM_CONFIGURE_FIELD_ENGINE_CUT_OFF   = "DigicamConfigure.EngineCutOff"
	DIGICAM_CONFIGURE_FIELD_EXTRA_PARAM      = "DigicamConfigure.ExtraParam"
)
View Source
const (
	DIGICAM_CONTROL_FIELD_EXTRA_VALUE      = "DigicamControl.ExtraValue"
	DIGICAM_CONTROL_FIELD_TARGET_SYSTEM    = "DigicamControl.TargetSystem"
	DIGICAM_CONTROL_FIELD_TARGET_COMPONENT = "DigicamControl.TargetComponent"
	DIGICAM_CONTROL_FIELD_SESSION          = "DigicamControl.Session"
	DIGICAM_CONTROL_FIELD_ZOOM_POS         = "DigicamControl.ZoomPos"
	DIGICAM_CONTROL_FIELD_ZOOM_STEP        = "DigicamControl.ZoomStep"
	DIGICAM_CONTROL_FIELD_FOCUS_LOCK       = "DigicamControl.FocusLock"
	DIGICAM_CONTROL_FIELD_SHOT             = "DigicamControl.Shot"
	DIGICAM_CONTROL_FIELD_COMMAND_ID       = "DigicamControl.CommandID"
	DIGICAM_CONTROL_FIELD_EXTRA_PARAM      = "DigicamControl.ExtraParam"
)
View Source
const (
	MOUNT_CONFIGURE_FIELD_TARGET_SYSTEM    = "MountConfigure.TargetSystem"
	MOUNT_CONFIGURE_FIELD_TARGET_COMPONENT = "MountConfigure.TargetComponent"
	MOUNT_CONFIGURE_FIELD_MOUNT_MODE       = "MountConfigure.MountMode"
	MOUNT_CONFIGURE_FIELD_STAB_ROLL        = "MountConfigure.StabRoll"
	MOUNT_CONFIGURE_FIELD_STAB_PITCH       = "MountConfigure.StabPitch"
	MOUNT_CONFIGURE_FIELD_STAB_YAW         = "MountConfigure.StabYaw"
)
View Source
const (
	MOUNT_CONTROL_FIELD_INPUT_A          = "MountControl.InputA"
	MOUNT_CONTROL_FIELD_INPUT_B          = "MountControl.InputB"
	MOUNT_CONTROL_FIELD_INPUT_C          = "MountControl.InputC"
	MOUNT_CONTROL_FIELD_TARGET_SYSTEM    = "MountControl.TargetSystem"
	MOUNT_CONTROL_FIELD_TARGET_COMPONENT = "MountControl.TargetComponent"
	MOUNT_CONTROL_FIELD_SAVE_POSITION    = "MountControl.SavePosition"
)
View Source
const (
	MOUNT_STATUS_FIELD_POINTING_A       = "MountStatus.PointingA"
	MOUNT_STATUS_FIELD_POINTING_B       = "MountStatus.PointingB"
	MOUNT_STATUS_FIELD_POINTING_C       = "MountStatus.PointingC"
	MOUNT_STATUS_FIELD_TARGET_SYSTEM    = "MountStatus.TargetSystem"
	MOUNT_STATUS_FIELD_TARGET_COMPONENT = "MountStatus.TargetComponent"
)
View Source
const (
	FENCE_POINT_FIELD_LAT              = "FencePoint.Lat"
	FENCE_POINT_FIELD_LNG              = "FencePoint.Lng"
	FENCE_POINT_FIELD_TARGET_SYSTEM    = "FencePoint.TargetSystem"
	FENCE_POINT_FIELD_TARGET_COMPONENT = "FencePoint.TargetComponent"
	FENCE_POINT_FIELD_IDX              = "FencePoint.Idx"
	FENCE_POINT_FIELD_COUNT            = "FencePoint.Count"
)
View Source
const (
	FENCE_FETCH_POINT_FIELD_TARGET_SYSTEM    = "FenceFetchPoint.TargetSystem"
	FENCE_FETCH_POINT_FIELD_TARGET_COMPONENT = "FenceFetchPoint.TargetComponent"
	FENCE_FETCH_POINT_FIELD_IDX              = "FenceFetchPoint.Idx"
)
View Source
const (
	AHRS_FIELD_OMEGAIX      = "Ahrs.Omegaix"
	AHRS_FIELD_OMEGAIY      = "Ahrs.Omegaiy"
	AHRS_FIELD_OMEGAIZ      = "Ahrs.Omegaiz"
	AHRS_FIELD_ACCEL_WEIGHT = "Ahrs.AccelWeight"
	AHRS_FIELD_RENORM_VAL   = "Ahrs.RenormVal"
	AHRS_FIELD_ERROR_RP     = "Ahrs.ErrorRp"
	AHRS_FIELD_ERROR_YAW    = "Ahrs.ErrorYaw"
)
View Source
const (
	SIMSTATE_FIELD_ROLL  = "Simstate.Roll"
	SIMSTATE_FIELD_PITCH = "Simstate.Pitch"
	SIMSTATE_FIELD_YAW   = "Simstate.Yaw"
	SIMSTATE_FIELD_XACC  = "Simstate.Xacc"
	SIMSTATE_FIELD_YACC  = "Simstate.Yacc"
	SIMSTATE_FIELD_ZACC  = "Simstate.Zacc"
	SIMSTATE_FIELD_XGYRO = "Simstate.Xgyro"
	SIMSTATE_FIELD_YGYRO = "Simstate.Ygyro"
	SIMSTATE_FIELD_ZGYRO = "Simstate.Zgyro"
	SIMSTATE_FIELD_LAT   = "Simstate.Lat"
	SIMSTATE_FIELD_LNG   = "Simstate.Lng"
)
View Source
const (
	HWSTATUS_FIELD_VCC    = "Hwstatus.Vcc"
	HWSTATUS_FIELD_I2CERR = "Hwstatus.I2cerr"
)
View Source
const (
	RADIO_FIELD_RXERRORS = "Radio.Rxerrors"
	RADIO_FIELD_FIXED    = "Radio.Fixed"
	RADIO_FIELD_RSSI     = "Radio.Rssi"
	RADIO_FIELD_REMRSSI  = "Radio.Remrssi"
	RADIO_FIELD_TXBUF    = "Radio.Txbuf"
	RADIO_FIELD_NOISE    = "Radio.Noise"
	RADIO_FIELD_REMNOISE = "Radio.Remnoise"
)
View Source
const (
	LIMITS_STATUS_FIELD_LAST_TRIGGER   = "LimitsStatus.LastTrigger"
	LIMITS_STATUS_FIELD_LAST_ACTION    = "LimitsStatus.LastAction"
	LIMITS_STATUS_FIELD_LAST_RECOVERY  = "LimitsStatus.LastRecovery"
	LIMITS_STATUS_FIELD_LAST_CLEAR     = "LimitsStatus.LastClear"
	LIMITS_STATUS_FIELD_BREACH_COUNT   = "LimitsStatus.BreachCount"
	LIMITS_STATUS_FIELD_LIMITS_STATE   = "LimitsStatus.LimitsState"
	LIMITS_STATUS_FIELD_MODS_ENABLED   = "LimitsStatus.ModsEnabled"
	LIMITS_STATUS_FIELD_MODS_REQUIRED  = "LimitsStatus.ModsRequired"
	LIMITS_STATUS_FIELD_MODS_TRIGGERED = "LimitsStatus.ModsTriggered"
)
View Source
const (
	WIND_FIELD_DIRECTION = "Wind.Direction"
	WIND_FIELD_SPEED     = "Wind.Speed"
	WIND_FIELD_SPEED_Z   = "Wind.SpeedZ"
)
View Source
const (
	DATA16_FIELD_TYPE = "Data16.Type"
	DATA16_FIELD_LEN  = "Data16.Len"
	DATA16_FIELD_DATA = "Data16.Data"
)
View Source
const (
	DATA32_FIELD_TYPE = "Data32.Type"
	DATA32_FIELD_LEN  = "Data32.Len"
	DATA32_FIELD_DATA = "Data32.Data"
)
View Source
const (
	DATA64_FIELD_TYPE = "Data64.Type"
	DATA64_FIELD_LEN  = "Data64.Len"
	DATA64_FIELD_DATA = "Data64.Data"
)
View Source
const (
	DATA96_FIELD_TYPE = "Data96.Type"
	DATA96_FIELD_LEN  = "Data96.Len"
	DATA96_FIELD_DATA = "Data96.Data"
)
View Source
const (
	RANGEFINDER_FIELD_DISTANCE = "Rangefinder.Distance"
	RANGEFINDER_FIELD_VOLTAGE  = "Rangefinder.Voltage"
)
View Source
const (
	AIRSPEED_AUTOCAL_FIELD_VX            = "AirspeedAutocal.Vx"
	AIRSPEED_AUTOCAL_FIELD_VY            = "AirspeedAutocal.Vy"
	AIRSPEED_AUTOCAL_FIELD_VZ            = "AirspeedAutocal.Vz"
	AIRSPEED_AUTOCAL_FIELD_DIFF_PRESSURE = "AirspeedAutocal.DiffPressure"
	AIRSPEED_AUTOCAL_FIELD_EAS2TAS       = "AirspeedAutocal.Eas2tas"
	AIRSPEED_AUTOCAL_FIELD_RATIO         = "AirspeedAutocal.Ratio"
	AIRSPEED_AUTOCAL_FIELD_STATE_X       = "AirspeedAutocal.StateX"
	AIRSPEED_AUTOCAL_FIELD_STATE_Y       = "AirspeedAutocal.StateY"
	AIRSPEED_AUTOCAL_FIELD_STATE_Z       = "AirspeedAutocal.StateZ"
	AIRSPEED_AUTOCAL_FIELD_PAX           = "AirspeedAutocal.Pax"
	AIRSPEED_AUTOCAL_FIELD_PBY           = "AirspeedAutocal.Pby"
	AIRSPEED_AUTOCAL_FIELD_PCZ           = "AirspeedAutocal.Pcz"
)
View Source
const (
	RALLY_POINT_FIELD_LAT              = "RallyPoint.Lat"
	RALLY_POINT_FIELD_LNG              = "RallyPoint.Lng"
	RALLY_POINT_FIELD_ALT              = "RallyPoint.Alt"
	RALLY_POINT_FIELD_BREAK_ALT        = "RallyPoint.BreakAlt"
	RALLY_POINT_FIELD_LAND_DIR         = "RallyPoint.LandDir"
	RALLY_POINT_FIELD_TARGET_SYSTEM    = "RallyPoint.TargetSystem"
	RALLY_POINT_FIELD_TARGET_COMPONENT = "RallyPoint.TargetComponent"
	RALLY_POINT_FIELD_IDX              = "RallyPoint.Idx"
	RALLY_POINT_FIELD_COUNT            = "RallyPoint.Count"
	RALLY_POINT_FIELD_FLAGS            = "RallyPoint.Flags"
)
View Source
const (
	RALLY_FETCH_POINT_FIELD_TARGET_SYSTEM    = "RallyFetchPoint.TargetSystem"
	RALLY_FETCH_POINT_FIELD_TARGET_COMPONENT = "RallyFetchPoint.TargetComponent"
	RALLY_FETCH_POINT_FIELD_IDX              = "RallyFetchPoint.Idx"
)
View Source
const (
	COMPASSMOT_STATUS_FIELD_CURRENT       = "CompassmotStatus.Current"
	COMPASSMOT_STATUS_FIELD_COMPENSATIONX = "CompassmotStatus.Compensationx"
	COMPASSMOT_STATUS_FIELD_COMPENSATIONY = "CompassmotStatus.Compensationy"
	COMPASSMOT_STATUS_FIELD_COMPENSATIONZ = "CompassmotStatus.Compensationz"
	COMPASSMOT_STATUS_FIELD_THROTTLE      = "CompassmotStatus.Throttle"
	COMPASSMOT_STATUS_FIELD_INTERFERENCE  = "CompassmotStatus.Interference"
)
View Source
const (
	AHRS2_FIELD_ROLL     = "Ahrs2.Roll"
	AHRS2_FIELD_PITCH    = "Ahrs2.Pitch"
	AHRS2_FIELD_YAW      = "Ahrs2.Yaw"
	AHRS2_FIELD_ALTITUDE = "Ahrs2.Altitude"
	AHRS2_FIELD_LAT      = "Ahrs2.Lat"
	AHRS2_FIELD_LNG      = "Ahrs2.Lng"
)
View Source
const (
	CAMERA_STATUS_FIELD_TIME_USEC     = "CameraStatus.TimeUsec"
	CAMERA_STATUS_FIELD_P1            = "CameraStatus.P1"
	CAMERA_STATUS_FIELD_P2            = "CameraStatus.P2"
	CAMERA_STATUS_FIELD_P3            = "CameraStatus.P3"
	CAMERA_STATUS_FIELD_P4            = "CameraStatus.P4"
	CAMERA_STATUS_FIELD_IMG_IDX       = "CameraStatus.ImgIdx"
	CAMERA_STATUS_FIELD_TARGET_SYSTEM = "CameraStatus.TargetSystem"
	CAMERA_STATUS_FIELD_CAM_IDX       = "CameraStatus.CamIdx"
	CAMERA_STATUS_FIELD_EVENT_ID      = "CameraStatus.EventID"
)
View Source
const (
	CAMERA_FEEDBACK_FIELD_TIME_USEC     = "CameraFeedback.TimeUsec"
	CAMERA_FEEDBACK_FIELD_LAT           = "CameraFeedback.Lat"
	CAMERA_FEEDBACK_FIELD_LNG           = "CameraFeedback.Lng"
	CAMERA_FEEDBACK_FIELD_ALT_MSL       = "CameraFeedback.AltMsl"
	CAMERA_FEEDBACK_FIELD_ALT_REL       = "CameraFeedback.AltRel"
	CAMERA_FEEDBACK_FIELD_ROLL          = "CameraFeedback.Roll"
	CAMERA_FEEDBACK_FIELD_PITCH         = "CameraFeedback.Pitch"
	CAMERA_FEEDBACK_FIELD_YAW           = "CameraFeedback.Yaw"
	CAMERA_FEEDBACK_FIELD_FOC_LEN       = "CameraFeedback.FocLen"
	CAMERA_FEEDBACK_FIELD_IMG_IDX       = "CameraFeedback.ImgIdx"
	CAMERA_FEEDBACK_FIELD_TARGET_SYSTEM = "CameraFeedback.TargetSystem"
	CAMERA_FEEDBACK_FIELD_CAM_IDX       = "CameraFeedback.CamIdx"
	CAMERA_FEEDBACK_FIELD_FLAGS         = "CameraFeedback.Flags"
)
View Source
const (
	BATTERY2_FIELD_VOLTAGE         = "Battery2.Voltage"
	BATTERY2_FIELD_CURRENT_BATTERY = "Battery2.CurrentBattery"
)
View Source
const (
	AHRS3_FIELD_ROLL     = "Ahrs3.Roll"
	AHRS3_FIELD_PITCH    = "Ahrs3.Pitch"
	AHRS3_FIELD_YAW      = "Ahrs3.Yaw"
	AHRS3_FIELD_ALTITUDE = "Ahrs3.Altitude"
	AHRS3_FIELD_LAT      = "Ahrs3.Lat"
	AHRS3_FIELD_LNG      = "Ahrs3.Lng"
	AHRS3_FIELD_V1       = "Ahrs3.V1"
	AHRS3_FIELD_V2       = "Ahrs3.V2"
	AHRS3_FIELD_V3       = "Ahrs3.V3"
	AHRS3_FIELD_V4       = "Ahrs3.V4"
)
View Source
const (
	AUTOPILOT_VERSION_REQUEST_FIELD_TARGET_SYSTEM    = "AutopilotVersionRequest.TargetSystem"
	AUTOPILOT_VERSION_REQUEST_FIELD_TARGET_COMPONENT = "AutopilotVersionRequest.TargetComponent"
)
View Source
const (
	REMOTE_LOG_DATA_BLOCK_FIELD_SEQNO            = "RemoteLogDataBlock.Seqno"
	REMOTE_LOG_DATA_BLOCK_FIELD_TARGET_SYSTEM    = "RemoteLogDataBlock.TargetSystem"
	REMOTE_LOG_DATA_BLOCK_FIELD_TARGET_COMPONENT = "RemoteLogDataBlock.TargetComponent"
	REMOTE_LOG_DATA_BLOCK_FIELD_DATA             = "RemoteLogDataBlock.Data"
)
View Source
const (
	REMOTE_LOG_BLOCK_STATUS_FIELD_SEQNO            = "RemoteLogBlockStatus.Seqno"
	REMOTE_LOG_BLOCK_STATUS_FIELD_TARGET_SYSTEM    = "RemoteLogBlockStatus.TargetSystem"
	REMOTE_LOG_BLOCK_STATUS_FIELD_TARGET_COMPONENT = "RemoteLogBlockStatus.TargetComponent"
	REMOTE_LOG_BLOCK_STATUS_FIELD_STATUS           = "RemoteLogBlockStatus.Status"
)
View Source
const (
	LED_CONTROL_FIELD_TARGET_SYSTEM    = "LedControl.TargetSystem"
	LED_CONTROL_FIELD_TARGET_COMPONENT = "LedControl.TargetComponent"
	LED_CONTROL_FIELD_INSTANCE         = "LedControl.Instance"
	LED_CONTROL_FIELD_PATTERN          = "LedControl.Pattern"
	LED_CONTROL_FIELD_CUSTOM_LEN       = "LedControl.CustomLen"
	LED_CONTROL_FIELD_CUSTOM_BYTES     = "LedControl.CustomBytes"
)
View Source
const (
	MAG_CAL_PROGRESS_FIELD_DIRECTION_X     = "MagCalProgress.DirectionX"
	MAG_CAL_PROGRESS_FIELD_DIRECTION_Y     = "MagCalProgress.DirectionY"
	MAG_CAL_PROGRESS_FIELD_DIRECTION_Z     = "MagCalProgress.DirectionZ"
	MAG_CAL_PROGRESS_FIELD_COMPASS_ID      = "MagCalProgress.CompassID"
	MAG_CAL_PROGRESS_FIELD_CAL_MASK        = "MagCalProgress.CalMask"
	MAG_CAL_PROGRESS_FIELD_CAL_STATUS      = "MagCalProgress.CalStatus"
	MAG_CAL_PROGRESS_FIELD_ATTEMPT         = "MagCalProgress.Attempt"
	MAG_CAL_PROGRESS_FIELD_COMPLETION_PCT  = "MagCalProgress.CompletionPct"
	MAG_CAL_PROGRESS_FIELD_COMPLETION_MASK = "MagCalProgress.CompletionMask"
)
View Source
const (
	EKF_STATUS_REPORT_FIELD_VELOCITY_VARIANCE    = "EkfStatusReport.VelocityVariance"
	EKF_STATUS_REPORT_FIELD_POS_HORIZ_VARIANCE   = "EkfStatusReport.PosHorizVariance"
	EKF_STATUS_REPORT_FIELD_POS_VERT_VARIANCE    = "EkfStatusReport.PosVertVariance"
	EKF_STATUS_REPORT_FIELD_COMPASS_VARIANCE     = "EkfStatusReport.CompassVariance"
	EKF_STATUS_REPORT_FIELD_TERRAIN_ALT_VARIANCE = "EkfStatusReport.TerrainAltVariance"
	EKF_STATUS_REPORT_FIELD_FLAGS                = "EkfStatusReport.Flags"
)
View Source
const (
	PID_TUNING_FIELD_DESIRED  = "PidTuning.Desired"
	PID_TUNING_FIELD_ACHIEVED = "PidTuning.Achieved"
	PID_TUNING_FIELD_FF       = "PidTuning.Ff"
	PID_TUNING_FIELD_P        = "PidTuning.P"
	PID_TUNING_FIELD_I        = "PidTuning.I"
	PID_TUNING_FIELD_D        = "PidTuning.D"
	PID_TUNING_FIELD_AXIS     = "PidTuning.Axis"
)
View Source
const (
	DEEPSTALL_FIELD_LANDING_LAT              = "Deepstall.LandingLat"
	DEEPSTALL_FIELD_LANDING_LON              = "Deepstall.LandingLon"
	DEEPSTALL_FIELD_PATH_LAT                 = "Deepstall.PathLat"
	DEEPSTALL_FIELD_PATH_LON                 = "Deepstall.PathLon"
	DEEPSTALL_FIELD_ARC_ENTRY_LAT            = "Deepstall.ArcEntryLat"
	DEEPSTALL_FIELD_ARC_ENTRY_LON            = "Deepstall.ArcEntryLon"
	DEEPSTALL_FIELD_ALTITUDE                 = "Deepstall.Altitude"
	DEEPSTALL_FIELD_EXPECTED_TRAVEL_DISTANCE = "Deepstall.ExpectedTravelDistance"
	DEEPSTALL_FIELD_CROSS_TRACK_ERROR        = "Deepstall.CrossTrackError"
	DEEPSTALL_FIELD_STAGE                    = "Deepstall.Stage"
)
View Source
const (
	GIMBAL_REPORT_FIELD_DELTA_TIME       = "GimbalReport.DeltaTime"
	GIMBAL_REPORT_FIELD_DELTA_ANGLE_X    = "GimbalReport.DeltaAngleX"
	GIMBAL_REPORT_FIELD_DELTA_ANGLE_Y    = "GimbalReport.DeltaAngleY"
	GIMBAL_REPORT_FIELD_DELTA_ANGLE_Z    = "GimbalReport.DeltaAngleZ"
	GIMBAL_REPORT_FIELD_DELTA_VELOCITY_X = "GimbalReport.DeltaVelocityX"
	GIMBAL_REPORT_FIELD_DELTA_VELOCITY_Y = "GimbalReport.DeltaVelocityY"
	GIMBAL_REPORT_FIELD_DELTA_VELOCITY_Z = "GimbalReport.DeltaVelocityZ"
	GIMBAL_REPORT_FIELD_JOINT_ROLL       = "GimbalReport.JointRoll"
	GIMBAL_REPORT_FIELD_JOINT_EL         = "GimbalReport.JointEl"
	GIMBAL_REPORT_FIELD_JOINT_AZ         = "GimbalReport.JointAz"
	GIMBAL_REPORT_FIELD_TARGET_SYSTEM    = "GimbalReport.TargetSystem"
	GIMBAL_REPORT_FIELD_TARGET_COMPONENT = "GimbalReport.TargetComponent"
)
View Source
const (
	GIMBAL_CONTROL_FIELD_DEMANDED_RATE_X  = "GimbalControl.DemandedRateX"
	GIMBAL_CONTROL_FIELD_DEMANDED_RATE_Y  = "GimbalControl.DemandedRateY"
	GIMBAL_CONTROL_FIELD_DEMANDED_RATE_Z  = "GimbalControl.DemandedRateZ"
	GIMBAL_CONTROL_FIELD_TARGET_SYSTEM    = "GimbalControl.TargetSystem"
	GIMBAL_CONTROL_FIELD_TARGET_COMPONENT = "GimbalControl.TargetComponent"
)
View Source
const (
	GIMBAL_TORQUE_CMD_REPORT_FIELD_RL_TORQUE_CMD    = "GimbalTorqueCmdReport.RlTorqueCmd"
	GIMBAL_TORQUE_CMD_REPORT_FIELD_EL_TORQUE_CMD    = "GimbalTorqueCmdReport.ElTorqueCmd"
	GIMBAL_TORQUE_CMD_REPORT_FIELD_AZ_TORQUE_CMD    = "GimbalTorqueCmdReport.AzTorqueCmd"
	GIMBAL_TORQUE_CMD_REPORT_FIELD_TARGET_SYSTEM    = "GimbalTorqueCmdReport.TargetSystem"
	GIMBAL_TORQUE_CMD_REPORT_FIELD_TARGET_COMPONENT = "GimbalTorqueCmdReport.TargetComponent"
)
View Source
const (
	GOPRO_HEARTBEAT_FIELD_STATUS       = "GoproHeartbeat.Status"
	GOPRO_HEARTBEAT_FIELD_CAPTURE_MODE = "GoproHeartbeat.CaptureMode"
	GOPRO_HEARTBEAT_FIELD_FLAGS        = "GoproHeartbeat.Flags"
)
View Source
const (
	GOPRO_GET_REQUEST_FIELD_TARGET_SYSTEM    = "GoproGetRequest.TargetSystem"
	GOPRO_GET_REQUEST_FIELD_TARGET_COMPONENT = "GoproGetRequest.TargetComponent"
	GOPRO_GET_REQUEST_FIELD_CMD_ID           = "GoproGetRequest.CmdID"
)
View Source
const (
	GOPRO_GET_RESPONSE_FIELD_CMD_ID = "GoproGetResponse.CmdID"
	GOPRO_GET_RESPONSE_FIELD_STATUS = "GoproGetResponse.Status"
	GOPRO_GET_RESPONSE_FIELD_VALUE  = "GoproGetResponse.Value"
)
View Source
const (
	GOPRO_SET_REQUEST_FIELD_TARGET_SYSTEM    = "GoproSetRequest.TargetSystem"
	GOPRO_SET_REQUEST_FIELD_TARGET_COMPONENT = "GoproSetRequest.TargetComponent"
	GOPRO_SET_REQUEST_FIELD_CMD_ID           = "GoproSetRequest.CmdID"
	GOPRO_SET_REQUEST_FIELD_VALUE            = "GoproSetRequest.Value"
)
View Source
const (
	GOPRO_SET_RESPONSE_FIELD_CMD_ID = "GoproSetResponse.CmdID"
	GOPRO_SET_RESPONSE_FIELD_STATUS = "GoproSetResponse.Status"
)
View Source
const (
	RPM_FIELD_RPM1 = "Rpm.Rpm1"
	RPM_FIELD_RPM2 = "Rpm.Rpm2"
)
View Source
const (
	SYS_STATUS_FIELD_ONBOARD_CONTROL_SENSORS_PRESENT = "SysStatus.OnboardControlSensorsPresent"
	SYS_STATUS_FIELD_ONBOARD_CONTROL_SENSORS_ENABLED = "SysStatus.OnboardControlSensorsEnabled"
	SYS_STATUS_FIELD_ONBOARD_CONTROL_SENSORS_HEALTH  = "SysStatus.OnboardControlSensorsHealth"
	SYS_STATUS_FIELD_LOAD                            = "SysStatus.Load"
	SYS_STATUS_FIELD_VOLTAGE_BATTERY                 = "SysStatus.VoltageBattery"
	SYS_STATUS_FIELD_CURRENT_BATTERY                 = "SysStatus.CurrentBattery"
	SYS_STATUS_FIELD_DROP_RATE_COMM                  = "SysStatus.DropRateComm"
	SYS_STATUS_FIELD_ERRORS_COMM                     = "SysStatus.ErrorsComm"
	SYS_STATUS_FIELD_ERRORS_COUNT1                   = "SysStatus.ErrorsCount1"
	SYS_STATUS_FIELD_ERRORS_COUNT2                   = "SysStatus.ErrorsCount2"
	SYS_STATUS_FIELD_ERRORS_COUNT3                   = "SysStatus.ErrorsCount3"
	SYS_STATUS_FIELD_ERRORS_COUNT4                   = "SysStatus.ErrorsCount4"
	SYS_STATUS_FIELD_BATTERY_REMAINING               = "SysStatus.BatteryRemaining"
)
View Source
const (
	SYSTEM_TIME_FIELD_TIME_UNIX_USEC = "SystemTime.TimeUnixUsec"
	SYSTEM_TIME_FIELD_TIME_BOOT_MS   = "SystemTime.TimeBootMs"
)
View Source
const (
	PING_FIELD_TIME_USEC        = "Ping.TimeUsec"
	PING_FIELD_SEQ              = "Ping.Seq"
	PING_FIELD_TARGET_SYSTEM    = "Ping.TargetSystem"
	PING_FIELD_TARGET_COMPONENT = "Ping.TargetComponent"
)
View Source
const (
	CHANGE_OPERATOR_CONTROL_FIELD_TARGET_SYSTEM   = "ChangeOperatorControl.TargetSystem"
	CHANGE_OPERATOR_CONTROL_FIELD_CONTROL_REQUEST = "ChangeOperatorControl.ControlRequest"
	CHANGE_OPERATOR_CONTROL_FIELD_VERSION         = "ChangeOperatorControl.Version"
	CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY         = "ChangeOperatorControl.Passkey"
)
View Source
const (
	CHANGE_OPERATOR_CONTROL_ACK_FIELD_GCS_SYSTEM_ID   = "ChangeOperatorControlAck.GcsSystemID"
	CHANGE_OPERATOR_CONTROL_ACK_FIELD_CONTROL_REQUEST = "ChangeOperatorControlAck.ControlRequest"
	CHANGE_OPERATOR_CONTROL_ACK_FIELD_ACK             = "ChangeOperatorControlAck.Ack"
)
View Source
const (
	LINK_NODE_STATUS_FIELD_TIMESTAMP         = "LinkNodeStatus.Timestamp"
	LINK_NODE_STATUS_FIELD_TX_RATE           = "LinkNodeStatus.TxRate"
	LINK_NODE_STATUS_FIELD_RX_RATE           = "LinkNodeStatus.RxRate"
	LINK_NODE_STATUS_FIELD_MESSAGES_SENT     = "LinkNodeStatus.MessagesSent"
	LINK_NODE_STATUS_FIELD_MESSAGES_RECEIVED = "LinkNodeStatus.MessagesReceived"
	LINK_NODE_STATUS_FIELD_MESSAGES_LOST     = "LinkNodeStatus.MessagesLost"
	LINK_NODE_STATUS_FIELD_RX_PARSE_ERR      = "LinkNodeStatus.RxParseErr"
	LINK_NODE_STATUS_FIELD_TX_OVERFLOWS      = "LinkNodeStatus.TxOverflows"
	LINK_NODE_STATUS_FIELD_RX_OVERFLOWS      = "LinkNodeStatus.RxOverflows"
	LINK_NODE_STATUS_FIELD_TX_BUF            = "LinkNodeStatus.TxBuf"
	LINK_NODE_STATUS_FIELD_RX_BUF            = "LinkNodeStatus.RxBuf"
)
View Source
const (
	SET_MODE_FIELD_CUSTOM_MODE   = "SetMode.CustomMode"
	SET_MODE_FIELD_TARGET_SYSTEM = "SetMode.TargetSystem"
	SET_MODE_FIELD_BASE_MODE     = "SetMode.BaseMode"
)
View Source
const (
	PARAM_ACK_TRANSACTION_FIELD_PARAM_VALUE      = "ParamAckTransaction.ParamValue"
	PARAM_ACK_TRANSACTION_FIELD_TARGET_SYSTEM    = "ParamAckTransaction.TargetSystem"
	PARAM_ACK_TRANSACTION_FIELD_TARGET_COMPONENT = "ParamAckTransaction.TargetComponent"
	PARAM_ACK_TRANSACTION_FIELD_PARAM_ID         = "ParamAckTransaction.ParamID"
	PARAM_ACK_TRANSACTION_FIELD_PARAM_TYPE       = "ParamAckTransaction.ParamType"
	PARAM_ACK_TRANSACTION_FIELD_PARAM_RESULT     = "ParamAckTransaction.ParamResult"
)
View Source
const (
	PARAM_REQUEST_READ_FIELD_PARAM_INDEX      = "ParamRequestRead.ParamIndex"
	PARAM_REQUEST_READ_FIELD_TARGET_SYSTEM    = "ParamRequestRead.TargetSystem"
	PARAM_REQUEST_READ_FIELD_TARGET_COMPONENT = "ParamRequestRead.TargetComponent"
	PARAM_REQUEST_READ_FIELD_PARAM_ID         = "ParamRequestRead.ParamID"
)
View Source
const (
	PARAM_REQUEST_LIST_FIELD_TARGET_SYSTEM    = "ParamRequestList.TargetSystem"
	PARAM_REQUEST_LIST_FIELD_TARGET_COMPONENT = "ParamRequestList.TargetComponent"
)
View Source
const (
	PARAM_VALUE_FIELD_PARAM_VALUE = "ParamValue.ParamValue"
	PARAM_VALUE_FIELD_PARAM_COUNT = "ParamValue.ParamCount"
	PARAM_VALUE_FIELD_PARAM_INDEX = "ParamValue.ParamIndex"
	PARAM_VALUE_FIELD_PARAM_ID    = "ParamValue.ParamID"
	PARAM_VALUE_FIELD_PARAM_TYPE  = "ParamValue.ParamType"
)
View Source
const (
	PARAM_SET_FIELD_PARAM_VALUE      = "ParamSet.ParamValue"
	PARAM_SET_FIELD_TARGET_SYSTEM    = "ParamSet.TargetSystem"
	PARAM_SET_FIELD_TARGET_COMPONENT = "ParamSet.TargetComponent"
	PARAM_SET_FIELD_PARAM_ID         = "ParamSet.ParamID"
	PARAM_SET_FIELD_PARAM_TYPE       = "ParamSet.ParamType"
)
View Source
const (
	GPS_RAW_INT_FIELD_TIME_USEC          = "GpsRawInt.TimeUsec"
	GPS_RAW_INT_FIELD_LAT                = "GpsRawInt.Lat"
	GPS_RAW_INT_FIELD_LON                = "GpsRawInt.Lon"
	GPS_RAW_INT_FIELD_ALT                = "GpsRawInt.Alt"
	GPS_RAW_INT_FIELD_EPH                = "GpsRawInt.Eph"
	GPS_RAW_INT_FIELD_EPV                = "GpsRawInt.Epv"
	GPS_RAW_INT_FIELD_VEL                = "GpsRawInt.Vel"
	GPS_RAW_INT_FIELD_COG                = "GpsRawInt.Cog"
	GPS_RAW_INT_FIELD_FIX_TYPE           = "GpsRawInt.FixType"
	GPS_RAW_INT_FIELD_SATELLITES_VISIBLE = "GpsRawInt.SatellitesVisible"
)
View Source
const (
	GPS_STATUS_FIELD_SATELLITES_VISIBLE  = "GpsStatus.SatellitesVisible"
	GPS_STATUS_FIELD_SATELLITE_PRN       = "GpsStatus.SatellitePrn"
	GPS_STATUS_FIELD_SATELLITE_USED      = "GpsStatus.SatelliteUsed"
	GPS_STATUS_FIELD_SATELLITE_ELEVATION = "GpsStatus.SatelliteElevation"
	GPS_STATUS_FIELD_SATELLITE_AZIMUTH   = "GpsStatus.SatelliteAzimuth"
	GPS_STATUS_FIELD_SATELLITE_SNR       = "GpsStatus.SatelliteSnr"
)
View Source
const (
	SCALED_IMU_FIELD_TIME_BOOT_MS = "ScaledImu.TimeBootMs"
	SCALED_IMU_FIELD_XACC         = "ScaledImu.Xacc"
	SCALED_IMU_FIELD_YACC         = "ScaledImu.Yacc"
	SCALED_IMU_FIELD_ZACC         = "ScaledImu.Zacc"
	SCALED_IMU_FIELD_XGYRO        = "ScaledImu.Xgyro"
	SCALED_IMU_FIELD_YGYRO        = "ScaledImu.Ygyro"
	SCALED_IMU_FIELD_ZGYRO        = "ScaledImu.Zgyro"
	SCALED_IMU_FIELD_XMAG         = "ScaledImu.Xmag"
	SCALED_IMU_FIELD_YMAG         = "ScaledImu.Ymag"
	SCALED_IMU_FIELD_ZMAG         = "ScaledImu.Zmag"
)
View Source
const (
	RAW_IMU_FIELD_TIME_USEC = "RawImu.TimeUsec"
	RAW_IMU_FIELD_XACC      = "RawImu.Xacc"
	RAW_IMU_FIELD_YACC      = "RawImu.Yacc"
	RAW_IMU_FIELD_ZACC      = "RawImu.Zacc"
	RAW_IMU_FIELD_XGYRO     = "RawImu.Xgyro"
	RAW_IMU_FIELD_YGYRO     = "RawImu.Ygyro"
	RAW_IMU_FIELD_ZGYRO     = "RawImu.Zgyro"
	RAW_IMU_FIELD_XMAG      = "RawImu.Xmag"
	RAW_IMU_FIELD_YMAG      = "RawImu.Ymag"
	RAW_IMU_FIELD_ZMAG      = "RawImu.Zmag"
)
View Source
const (
	RAW_PRESSURE_FIELD_TIME_USEC   = "RawPressure.TimeUsec"
	RAW_PRESSURE_FIELD_PRESS_ABS   = "RawPressure.PressAbs"
	RAW_PRESSURE_FIELD_PRESS_DIFF1 = "RawPressure.PressDiff1"
	RAW_PRESSURE_FIELD_PRESS_DIFF2 = "RawPressure.PressDiff2"
	RAW_PRESSURE_FIELD_TEMPERATURE = "RawPressure.Temperature"
)
View Source
const (
	SCALED_PRESSURE_FIELD_TIME_BOOT_MS = "ScaledPressure.TimeBootMs"
	SCALED_PRESSURE_FIELD_PRESS_ABS    = "ScaledPressure.PressAbs"
	SCALED_PRESSURE_FIELD_PRESS_DIFF   = "ScaledPressure.PressDiff"
	SCALED_PRESSURE_FIELD_TEMPERATURE  = "ScaledPressure.Temperature"
)
View Source
const (
	ATTITUDE_FIELD_TIME_BOOT_MS = "Attitude.TimeBootMs"
	ATTITUDE_FIELD_ROLL         = "Attitude.Roll"
	ATTITUDE_FIELD_PITCH        = "Attitude.Pitch"
	ATTITUDE_FIELD_YAW          = "Attitude.Yaw"
	ATTITUDE_FIELD_ROLLSPEED    = "Attitude.Rollspeed"
	ATTITUDE_FIELD_PITCHSPEED   = "Attitude.Pitchspeed"
	ATTITUDE_FIELD_YAWSPEED     = "Attitude.Yawspeed"
)
View Source
const (
	ATTITUDE_QUATERNION_FIELD_TIME_BOOT_MS = "AttitudeQuaternion.TimeBootMs"
	ATTITUDE_QUATERNION_FIELD_Q1           = "AttitudeQuaternion.Q1"
	ATTITUDE_QUATERNION_FIELD_Q2           = "AttitudeQuaternion.Q2"
	ATTITUDE_QUATERNION_FIELD_Q3           = "AttitudeQuaternion.Q3"
	ATTITUDE_QUATERNION_FIELD_Q4           = "AttitudeQuaternion.Q4"
	ATTITUDE_QUATERNION_FIELD_ROLLSPEED    = "AttitudeQuaternion.Rollspeed"
	ATTITUDE_QUATERNION_FIELD_PITCHSPEED   = "AttitudeQuaternion.Pitchspeed"
	ATTITUDE_QUATERNION_FIELD_YAWSPEED     = "AttitudeQuaternion.Yawspeed"
)
View Source
const (
	LOCAL_POSITION_NED_FIELD_TIME_BOOT_MS = "LocalPositionNed.TimeBootMs"
	LOCAL_POSITION_NED_FIELD_X            = "LocalPositionNed.X"
	LOCAL_POSITION_NED_FIELD_Y            = "LocalPositionNed.Y"
	LOCAL_POSITION_NED_FIELD_Z            = "LocalPositionNed.Z"
	LOCAL_POSITION_NED_FIELD_VX           = "LocalPositionNed.Vx"
	LOCAL_POSITION_NED_FIELD_VY           = "LocalPositionNed.Vy"
	LOCAL_POSITION_NED_FIELD_VZ           = "LocalPositionNed.Vz"
)
View Source
const (
	GLOBAL_POSITION_INT_FIELD_TIME_BOOT_MS = "GlobalPositionInt.TimeBootMs"
	GLOBAL_POSITION_INT_FIELD_LAT          = "GlobalPositionInt.Lat"
	GLOBAL_POSITION_INT_FIELD_LON          = "GlobalPositionInt.Lon"
	GLOBAL_POSITION_INT_FIELD_ALT          = "GlobalPositionInt.Alt"
	GLOBAL_POSITION_INT_FIELD_RELATIVE_ALT = "GlobalPositionInt.RelativeAlt"
	GLOBAL_POSITION_INT_FIELD_VX           = "GlobalPositionInt.Vx"
	GLOBAL_POSITION_INT_FIELD_VY           = "GlobalPositionInt.Vy"
	GLOBAL_POSITION_INT_FIELD_VZ           = "GlobalPositionInt.Vz"
	GLOBAL_POSITION_INT_FIELD_HDG          = "GlobalPositionInt.Hdg"
)
View Source
const (
	RC_CHANNELS_SCALED_FIELD_TIME_BOOT_MS = "RcChannelsScaled.TimeBootMs"
	RC_CHANNELS_SCALED_FIELD_CHAN1_SCALED = "RcChannelsScaled.Chan1Scaled"
	RC_CHANNELS_SCALED_FIELD_CHAN2_SCALED = "RcChannelsScaled.Chan2Scaled"
	RC_CHANNELS_SCALED_FIELD_CHAN3_SCALED = "RcChannelsScaled.Chan3Scaled"
	RC_CHANNELS_SCALED_FIELD_CHAN4_SCALED = "RcChannelsScaled.Chan4Scaled"
	RC_CHANNELS_SCALED_FIELD_CHAN5_SCALED = "RcChannelsScaled.Chan5Scaled"
	RC_CHANNELS_SCALED_FIELD_CHAN6_SCALED = "RcChannelsScaled.Chan6Scaled"
	RC_CHANNELS_SCALED_FIELD_CHAN7_SCALED = "RcChannelsScaled.Chan7Scaled"
	RC_CHANNELS_SCALED_FIELD_CHAN8_SCALED = "RcChannelsScaled.Chan8Scaled"
	RC_CHANNELS_SCALED_FIELD_PORT         = "RcChannelsScaled.Port"
	RC_CHANNELS_SCALED_FIELD_RSSI         = "RcChannelsScaled.Rssi"
)
View Source
const (
	RC_CHANNELS_RAW_FIELD_TIME_BOOT_MS = "RcChannelsRaw.TimeBootMs"
	RC_CHANNELS_RAW_FIELD_CHAN1_RAW    = "RcChannelsRaw.Chan1Raw"
	RC_CHANNELS_RAW_FIELD_CHAN2_RAW    = "RcChannelsRaw.Chan2Raw"
	RC_CHANNELS_RAW_FIELD_CHAN3_RAW    = "RcChannelsRaw.Chan3Raw"
	RC_CHANNELS_RAW_FIELD_CHAN4_RAW    = "RcChannelsRaw.Chan4Raw"
	RC_CHANNELS_RAW_FIELD_CHAN5_RAW    = "RcChannelsRaw.Chan5Raw"
	RC_CHANNELS_RAW_FIELD_CHAN6_RAW    = "RcChannelsRaw.Chan6Raw"
	RC_CHANNELS_RAW_FIELD_CHAN7_RAW    = "RcChannelsRaw.Chan7Raw"
	RC_CHANNELS_RAW_FIELD_CHAN8_RAW    = "RcChannelsRaw.Chan8Raw"
	RC_CHANNELS_RAW_FIELD_PORT         = "RcChannelsRaw.Port"
	RC_CHANNELS_RAW_FIELD_RSSI         = "RcChannelsRaw.Rssi"
)
View Source
const (
	SERVO_OUTPUT_RAW_FIELD_TIME_USEC  = "ServoOutputRaw.TimeUsec"
	SERVO_OUTPUT_RAW_FIELD_SERVO1_RAW = "ServoOutputRaw.Servo1Raw"
	SERVO_OUTPUT_RAW_FIELD_SERVO2_RAW = "ServoOutputRaw.Servo2Raw"
	SERVO_OUTPUT_RAW_FIELD_SERVO3_RAW = "ServoOutputRaw.Servo3Raw"
	SERVO_OUTPUT_RAW_FIELD_SERVO4_RAW = "ServoOutputRaw.Servo4Raw"
	SERVO_OUTPUT_RAW_FIELD_SERVO5_RAW = "ServoOutputRaw.Servo5Raw"
	SERVO_OUTPUT_RAW_FIELD_SERVO6_RAW = "ServoOutputRaw.Servo6Raw"
	SERVO_OUTPUT_RAW_FIELD_SERVO7_RAW = "ServoOutputRaw.Servo7Raw"
	SERVO_OUTPUT_RAW_FIELD_SERVO8_RAW = "ServoOutputRaw.Servo8Raw"
	SERVO_OUTPUT_RAW_FIELD_PORT       = "ServoOutputRaw.Port"
)
View Source
const (
	MISSION_REQUEST_PARTIAL_LIST_FIELD_START_INDEX      = "MissionRequestPartialList.StartIndex"
	MISSION_REQUEST_PARTIAL_LIST_FIELD_END_INDEX        = "MissionRequestPartialList.EndIndex"
	MISSION_REQUEST_PARTIAL_LIST_FIELD_TARGET_SYSTEM    = "MissionRequestPartialList.TargetSystem"
	MISSION_REQUEST_PARTIAL_LIST_FIELD_TARGET_COMPONENT = "MissionRequestPartialList.TargetComponent"
)
View Source
const (
	MISSION_WRITE_PARTIAL_LIST_FIELD_START_INDEX      = "MissionWritePartialList.StartIndex"
	MISSION_WRITE_PARTIAL_LIST_FIELD_END_INDEX        = "MissionWritePartialList.EndIndex"
	MISSION_WRITE_PARTIAL_LIST_FIELD_TARGET_SYSTEM    = "MissionWritePartialList.TargetSystem"
	MISSION_WRITE_PARTIAL_LIST_FIELD_TARGET_COMPONENT = "MissionWritePartialList.TargetComponent"
)
View Source
const (
	MISSION_ITEM_FIELD_PARAM1           = "MissionItem.Param1"
	MISSION_ITEM_FIELD_PARAM2           = "MissionItem.Param2"
	MISSION_ITEM_FIELD_PARAM3           = "MissionItem.Param3"
	MISSION_ITEM_FIELD_PARAM4           = "MissionItem.Param4"
	MISSION_ITEM_FIELD_X                = "MissionItem.X"
	MISSION_ITEM_FIELD_Y                = "MissionItem.Y"
	MISSION_ITEM_FIELD_Z                = "MissionItem.Z"
	MISSION_ITEM_FIELD_SEQ              = "MissionItem.Seq"
	MISSION_ITEM_FIELD_COMMAND          = "MissionItem.Command"
	MISSION_ITEM_FIELD_TARGET_SYSTEM    = "MissionItem.TargetSystem"
	MISSION_ITEM_FIELD_TARGET_COMPONENT = "MissionItem.TargetComponent"
	MISSION_ITEM_FIELD_FRAME            = "MissionItem.Frame"
	MISSION_ITEM_FIELD_CURRENT          = "MissionItem.Current"
	MISSION_ITEM_FIELD_AUTOCONTINUE     = "MissionItem.Autocontinue"
)
View Source
const (
	MISSION_REQUEST_FIELD_SEQ              = "MissionRequest.Seq"
	MISSION_REQUEST_FIELD_TARGET_SYSTEM    = "MissionRequest.TargetSystem"
	MISSION_REQUEST_FIELD_TARGET_COMPONENT = "MissionRequest.TargetComponent"
)
View Source
const (
	MISSION_SET_CURRENT_FIELD_SEQ              = "MissionSetCurrent.Seq"
	MISSION_SET_CURRENT_FIELD_TARGET_SYSTEM    = "MissionSetCurrent.TargetSystem"
	MISSION_SET_CURRENT_FIELD_TARGET_COMPONENT = "MissionSetCurrent.TargetComponent"
)
View Source
const (
	MISSION_REQUEST_LIST_FIELD_TARGET_SYSTEM    = "MissionRequestList.TargetSystem"
	MISSION_REQUEST_LIST_FIELD_TARGET_COMPONENT = "MissionRequestList.TargetComponent"
)
View Source
const (
	MISSION_COUNT_FIELD_COUNT            = "MissionCount.Count"
	MISSION_COUNT_FIELD_TARGET_SYSTEM    = "MissionCount.TargetSystem"
	MISSION_COUNT_FIELD_TARGET_COMPONENT = "MissionCount.TargetComponent"
)
View Source
const (
	MISSION_CLEAR_ALL_FIELD_TARGET_SYSTEM    = "MissionClearAll.TargetSystem"
	MISSION_CLEAR_ALL_FIELD_TARGET_COMPONENT = "MissionClearAll.TargetComponent"
)
View Source
const (
	MISSION_ACK_FIELD_TARGET_SYSTEM    = "MissionAck.TargetSystem"
	MISSION_ACK_FIELD_TARGET_COMPONENT = "MissionAck.TargetComponent"
	MISSION_ACK_FIELD_TYPE             = "MissionAck.Type"
)
View Source
const (
	SET_GPS_GLOBAL_ORIGIN_FIELD_LATITUDE      = "SetGpsGlobalOrigin.Latitude"
	SET_GPS_GLOBAL_ORIGIN_FIELD_LONGITUDE     = "SetGpsGlobalOrigin.Longitude"
	SET_GPS_GLOBAL_ORIGIN_FIELD_ALTITUDE      = "SetGpsGlobalOrigin.Altitude"
	SET_GPS_GLOBAL_ORIGIN_FIELD_TARGET_SYSTEM = "SetGpsGlobalOrigin.TargetSystem"
)
View Source
const (
	GPS_GLOBAL_ORIGIN_FIELD_LATITUDE  = "GpsGlobalOrigin.Latitude"
	GPS_GLOBAL_ORIGIN_FIELD_LONGITUDE = "GpsGlobalOrigin.Longitude"
	GPS_GLOBAL_ORIGIN_FIELD_ALTITUDE  = "GpsGlobalOrigin.Altitude"
)
View Source
const (
	PARAM_MAP_RC_FIELD_PARAM_VALUE0               = "ParamMapRc.ParamValue0"
	PARAM_MAP_RC_FIELD_SCALE                      = "ParamMapRc.Scale"
	PARAM_MAP_RC_FIELD_PARAM_VALUE_MIN            = "ParamMapRc.ParamValueMin"
	PARAM_MAP_RC_FIELD_PARAM_VALUE_MAX            = "ParamMapRc.ParamValueMax"
	PARAM_MAP_RC_FIELD_PARAM_INDEX                = "ParamMapRc.ParamIndex"
	PARAM_MAP_RC_FIELD_TARGET_SYSTEM              = "ParamMapRc.TargetSystem"
	PARAM_MAP_RC_FIELD_TARGET_COMPONENT           = "ParamMapRc.TargetComponent"
	PARAM_MAP_RC_FIELD_PARAM_ID                   = "ParamMapRc.ParamID"
	PARAM_MAP_RC_FIELD_PARAMETER_RC_CHANNEL_INDEX = "ParamMapRc.ParameterRcChannelIndex"
)
View Source
const (
	MISSION_REQUEST_INT_FIELD_SEQ              = "MissionRequestInt.Seq"
	MISSION_REQUEST_INT_FIELD_TARGET_SYSTEM    = "MissionRequestInt.TargetSystem"
	MISSION_REQUEST_INT_FIELD_TARGET_COMPONENT = "MissionRequestInt.TargetComponent"
)
View Source
const (
	MISSION_CHANGED_FIELD_START_INDEX   = "MissionChanged.StartIndex"
	MISSION_CHANGED_FIELD_END_INDEX     = "MissionChanged.EndIndex"
	MISSION_CHANGED_FIELD_ORIGIN_SYSID  = "MissionChanged.OriginSysid"
	MISSION_CHANGED_FIELD_ORIGIN_COMPID = "MissionChanged.OriginCompid"
	MISSION_CHANGED_FIELD_MISSION_TYPE  = "MissionChanged.MissionType"
)
View Source
const (
	SAFETY_SET_ALLOWED_AREA_FIELD_P1X              = "SafetySetAllowedArea.P1x"
	SAFETY_SET_ALLOWED_AREA_FIELD_P1Y              = "SafetySetAllowedArea.P1y"
	SAFETY_SET_ALLOWED_AREA_FIELD_P1Z              = "SafetySetAllowedArea.P1z"
	SAFETY_SET_ALLOWED_AREA_FIELD_P2X              = "SafetySetAllowedArea.P2x"
	SAFETY_SET_ALLOWED_AREA_FIELD_P2Y              = "SafetySetAllowedArea.P2y"
	SAFETY_SET_ALLOWED_AREA_FIELD_P2Z              = "SafetySetAllowedArea.P2z"
	SAFETY_SET_ALLOWED_AREA_FIELD_TARGET_SYSTEM    = "SafetySetAllowedArea.TargetSystem"
	SAFETY_SET_ALLOWED_AREA_FIELD_TARGET_COMPONENT = "SafetySetAllowedArea.TargetComponent"
	SAFETY_SET_ALLOWED_AREA_FIELD_FRAME            = "SafetySetAllowedArea.Frame"
)
View Source
const (
	SAFETY_ALLOWED_AREA_FIELD_P1X   = "SafetyAllowedArea.P1x"
	SAFETY_ALLOWED_AREA_FIELD_P1Y   = "SafetyAllowedArea.P1y"
	SAFETY_ALLOWED_AREA_FIELD_P1Z   = "SafetyAllowedArea.P1z"
	SAFETY_ALLOWED_AREA_FIELD_P2X   = "SafetyAllowedArea.P2x"
	SAFETY_ALLOWED_AREA_FIELD_P2Y   = "SafetyAllowedArea.P2y"
	SAFETY_ALLOWED_AREA_FIELD_P2Z   = "SafetyAllowedArea.P2z"
	SAFETY_ALLOWED_AREA_FIELD_FRAME = "SafetyAllowedArea.Frame"
)
View Source
const (
	ATTITUDE_QUATERNION_COV_FIELD_TIME_USEC  = "AttitudeQuaternionCov.TimeUsec"
	ATTITUDE_QUATERNION_COV_FIELD_Q          = "AttitudeQuaternionCov.Q"
	ATTITUDE_QUATERNION_COV_FIELD_ROLLSPEED  = "AttitudeQuaternionCov.Rollspeed"
	ATTITUDE_QUATERNION_COV_FIELD_PITCHSPEED = "AttitudeQuaternionCov.Pitchspeed"
	ATTITUDE_QUATERNION_COV_FIELD_YAWSPEED   = "AttitudeQuaternionCov.Yawspeed"
	ATTITUDE_QUATERNION_COV_FIELD_COVARIANCE = "AttitudeQuaternionCov.Covariance"
)
View Source
const (
	NAV_CONTROLLER_OUTPUT_FIELD_NAV_ROLL       = "NavControllerOutput.NavRoll"
	NAV_CONTROLLER_OUTPUT_FIELD_NAV_PITCH      = "NavControllerOutput.NavPitch"
	NAV_CONTROLLER_OUTPUT_FIELD_ALT_ERROR      = "NavControllerOutput.AltError"
	NAV_CONTROLLER_OUTPUT_FIELD_ASPD_ERROR     = "NavControllerOutput.AspdError"
	NAV_CONTROLLER_OUTPUT_FIELD_XTRACK_ERROR   = "NavControllerOutput.XtrackError"
	NAV_CONTROLLER_OUTPUT_FIELD_NAV_BEARING    = "NavControllerOutput.NavBearing"
	NAV_CONTROLLER_OUTPUT_FIELD_TARGET_BEARING = "NavControllerOutput.TargetBearing"
	NAV_CONTROLLER_OUTPUT_FIELD_WP_DIST        = "NavControllerOutput.WpDist"
)
View Source
const (
	GLOBAL_POSITION_INT_COV_FIELD_TIME_USEC      = "GlobalPositionIntCov.TimeUsec"
	GLOBAL_POSITION_INT_COV_FIELD_LAT            = "GlobalPositionIntCov.Lat"
	GLOBAL_POSITION_INT_COV_FIELD_LON            = "GlobalPositionIntCov.Lon"
	GLOBAL_POSITION_INT_COV_FIELD_ALT            = "GlobalPositionIntCov.Alt"
	GLOBAL_POSITION_INT_COV_FIELD_RELATIVE_ALT   = "GlobalPositionIntCov.RelativeAlt"
	GLOBAL_POSITION_INT_COV_FIELD_VX             = "GlobalPositionIntCov.Vx"
	GLOBAL_POSITION_INT_COV_FIELD_VY             = "GlobalPositionIntCov.Vy"
	GLOBAL_POSITION_INT_COV_FIELD_VZ             = "GlobalPositionIntCov.Vz"
	GLOBAL_POSITION_INT_COV_FIELD_COVARIANCE     = "GlobalPositionIntCov.Covariance"
	GLOBAL_POSITION_INT_COV_FIELD_ESTIMATOR_TYPE = "GlobalPositionIntCov.EstimatorType"
)
View Source
const (
	LOCAL_POSITION_NED_COV_FIELD_TIME_USEC      = "LocalPositionNedCov.TimeUsec"
	LOCAL_POSITION_NED_COV_FIELD_X              = "LocalPositionNedCov.X"
	LOCAL_POSITION_NED_COV_FIELD_Y              = "LocalPositionNedCov.Y"
	LOCAL_POSITION_NED_COV_FIELD_Z              = "LocalPositionNedCov.Z"
	LOCAL_POSITION_NED_COV_FIELD_VX             = "LocalPositionNedCov.Vx"
	LOCAL_POSITION_NED_COV_FIELD_VY             = "LocalPositionNedCov.Vy"
	LOCAL_POSITION_NED_COV_FIELD_VZ             = "LocalPositionNedCov.Vz"
	LOCAL_POSITION_NED_COV_FIELD_AX             = "LocalPositionNedCov.Ax"
	LOCAL_POSITION_NED_COV_FIELD_AY             = "LocalPositionNedCov.Ay"
	LOCAL_POSITION_NED_COV_FIELD_AZ             = "LocalPositionNedCov.Az"
	LOCAL_POSITION_NED_COV_FIELD_COVARIANCE     = "LocalPositionNedCov.Covariance"
	LOCAL_POSITION_NED_COV_FIELD_ESTIMATOR_TYPE = "LocalPositionNedCov.EstimatorType"
)
View Source
const (
	RC_CHANNELS_FIELD_TIME_BOOT_MS = "RcChannels.TimeBootMs"
	RC_CHANNELS_FIELD_CHAN1_RAW    = "RcChannels.Chan1Raw"
	RC_CHANNELS_FIELD_CHAN2_RAW    = "RcChannels.Chan2Raw"
	RC_CHANNELS_FIELD_CHAN3_RAW    = "RcChannels.Chan3Raw"
	RC_CHANNELS_FIELD_CHAN4_RAW    = "RcChannels.Chan4Raw"
	RC_CHANNELS_FIELD_CHAN5_RAW    = "RcChannels.Chan5Raw"
	RC_CHANNELS_FIELD_CHAN6_RAW    = "RcChannels.Chan6Raw"
	RC_CHANNELS_FIELD_CHAN7_RAW    = "RcChannels.Chan7Raw"
	RC_CHANNELS_FIELD_CHAN8_RAW    = "RcChannels.Chan8Raw"
	RC_CHANNELS_FIELD_CHAN9_RAW    = "RcChannels.Chan9Raw"
	RC_CHANNELS_FIELD_CHAN10_RAW   = "RcChannels.Chan10Raw"
	RC_CHANNELS_FIELD_CHAN11_RAW   = "RcChannels.Chan11Raw"
	RC_CHANNELS_FIELD_CHAN12_RAW   = "RcChannels.Chan12Raw"
	RC_CHANNELS_FIELD_CHAN13_RAW   = "RcChannels.Chan13Raw"
	RC_CHANNELS_FIELD_CHAN14_RAW   = "RcChannels.Chan14Raw"
	RC_CHANNELS_FIELD_CHAN15_RAW   = "RcChannels.Chan15Raw"
	RC_CHANNELS_FIELD_CHAN16_RAW   = "RcChannels.Chan16Raw"
	RC_CHANNELS_FIELD_CHAN17_RAW   = "RcChannels.Chan17Raw"
	RC_CHANNELS_FIELD_CHAN18_RAW   = "RcChannels.Chan18Raw"
	RC_CHANNELS_FIELD_CHANCOUNT    = "RcChannels.Chancount"
	RC_CHANNELS_FIELD_RSSI         = "RcChannels.Rssi"
)
View Source
const (
	REQUEST_DATA_STREAM_FIELD_REQ_MESSAGE_RATE = "RequestDataStream.ReqMessageRate"
	REQUEST_DATA_STREAM_FIELD_TARGET_SYSTEM    = "RequestDataStream.TargetSystem"
	REQUEST_DATA_STREAM_FIELD_TARGET_COMPONENT = "RequestDataStream.TargetComponent"
	REQUEST_DATA_STREAM_FIELD_REQ_STREAM_ID    = "RequestDataStream.ReqStreamID"
	REQUEST_DATA_STREAM_FIELD_START_STOP       = "RequestDataStream.StartStop"
)
View Source
const (
	DATA_STREAM_FIELD_MESSAGE_RATE = "DataStream.MessageRate"
	DATA_STREAM_FIELD_STREAM_ID    = "DataStream.StreamID"
	DATA_STREAM_FIELD_ON_OFF       = "DataStream.OnOff"
)
View Source
const (
	MANUAL_CONTROL_FIELD_X       = "ManualControl.X"
	MANUAL_CONTROL_FIELD_Y       = "ManualControl.Y"
	MANUAL_CONTROL_FIELD_Z       = "ManualControl.Z"
	MANUAL_CONTROL_FIELD_R       = "ManualControl.R"
	MANUAL_CONTROL_FIELD_BUTTONS = "ManualControl.Buttons"
	MANUAL_CONTROL_FIELD_TARGET  = "ManualControl.Target"
)
View Source
const (
	RC_CHANNELS_OVERRIDE_FIELD_CHAN1_RAW        = "RcChannelsOverride.Chan1Raw"
	RC_CHANNELS_OVERRIDE_FIELD_CHAN2_RAW        = "RcChannelsOverride.Chan2Raw"
	RC_CHANNELS_OVERRIDE_FIELD_CHAN3_RAW        = "RcChannelsOverride.Chan3Raw"
	RC_CHANNELS_OVERRIDE_FIELD_CHAN4_RAW        = "RcChannelsOverride.Chan4Raw"
	RC_CHANNELS_OVERRIDE_FIELD_CHAN5_RAW        = "RcChannelsOverride.Chan5Raw"
	RC_CHANNELS_OVERRIDE_FIELD_CHAN6_RAW        = "RcChannelsOverride.Chan6Raw"
	RC_CHANNELS_OVERRIDE_FIELD_CHAN7_RAW        = "RcChannelsOverride.Chan7Raw"
	RC_CHANNELS_OVERRIDE_FIELD_CHAN8_RAW        = "RcChannelsOverride.Chan8Raw"
	RC_CHANNELS_OVERRIDE_FIELD_TARGET_SYSTEM    = "RcChannelsOverride.TargetSystem"
	RC_CHANNELS_OVERRIDE_FIELD_TARGET_COMPONENT = "RcChannelsOverride.TargetComponent"
)
View Source
const (
	MISSION_ITEM_INT_FIELD_PARAM1           = "MissionItemInt.Param1"
	MISSION_ITEM_INT_FIELD_PARAM2           = "MissionItemInt.Param2"
	MISSION_ITEM_INT_FIELD_PARAM3           = "MissionItemInt.Param3"
	MISSION_ITEM_INT_FIELD_PARAM4           = "MissionItemInt.Param4"
	MISSION_ITEM_INT_FIELD_X                = "MissionItemInt.X"
	MISSION_ITEM_INT_FIELD_Y                = "MissionItemInt.Y"
	MISSION_ITEM_INT_FIELD_Z                = "MissionItemInt.Z"
	MISSION_ITEM_INT_FIELD_SEQ              = "MissionItemInt.Seq"
	MISSION_ITEM_INT_FIELD_COMMAND          = "MissionItemInt.Command"
	MISSION_ITEM_INT_FIELD_TARGET_SYSTEM    = "MissionItemInt.TargetSystem"
	MISSION_ITEM_INT_FIELD_TARGET_COMPONENT = "MissionItemInt.TargetComponent"
	MISSION_ITEM_INT_FIELD_FRAME            = "MissionItemInt.Frame"
	MISSION_ITEM_INT_FIELD_CURRENT          = "MissionItemInt.Current"
	MISSION_ITEM_INT_FIELD_AUTOCONTINUE     = "MissionItemInt.Autocontinue"
)
View Source
const (
	VFR_HUD_FIELD_AIRSPEED    = "VfrHud.Airspeed"
	VFR_HUD_FIELD_GROUNDSPEED = "VfrHud.Groundspeed"
	VFR_HUD_FIELD_ALT         = "VfrHud.Alt"
	VFR_HUD_FIELD_CLIMB       = "VfrHud.Climb"
	VFR_HUD_FIELD_HEADING     = "VfrHud.Heading"
	VFR_HUD_FIELD_THROTTLE    = "VfrHud.Throttle"
)
View Source
const (
	COMMAND_INT_FIELD_PARAM1           = "CommandInt.Param1"
	COMMAND_INT_FIELD_PARAM2           = "CommandInt.Param2"
	COMMAND_INT_FIELD_PARAM3           = "CommandInt.Param3"
	COMMAND_INT_FIELD_PARAM4           = "CommandInt.Param4"
	COMMAND_INT_FIELD_X                = "CommandInt.X"
	COMMAND_INT_FIELD_Y                = "CommandInt.Y"
	COMMAND_INT_FIELD_Z                = "CommandInt.Z"
	COMMAND_INT_FIELD_COMMAND          = "CommandInt.Command"
	COMMAND_INT_FIELD_TARGET_SYSTEM    = "CommandInt.TargetSystem"
	COMMAND_INT_FIELD_TARGET_COMPONENT = "CommandInt.TargetComponent"
	COMMAND_INT_FIELD_FRAME            = "CommandInt.Frame"
	COMMAND_INT_FIELD_CURRENT          = "CommandInt.Current"
	COMMAND_INT_FIELD_AUTOCONTINUE     = "CommandInt.Autocontinue"
)
View Source
const (
	COMMAND_LONG_FIELD_PARAM1           = "CommandLong.Param1"
	COMMAND_LONG_FIELD_PARAM2           = "CommandLong.Param2"
	COMMAND_LONG_FIELD_PARAM3           = "CommandLong.Param3"
	COMMAND_LONG_FIELD_PARAM4           = "CommandLong.Param4"
	COMMAND_LONG_FIELD_PARAM5           = "CommandLong.Param5"
	COMMAND_LONG_FIELD_PARAM6           = "CommandLong.Param6"
	COMMAND_LONG_FIELD_PARAM7           = "CommandLong.Param7"
	COMMAND_LONG_FIELD_COMMAND          = "CommandLong.Command"
	COMMAND_LONG_FIELD_TARGET_SYSTEM    = "CommandLong.TargetSystem"
	COMMAND_LONG_FIELD_TARGET_COMPONENT = "CommandLong.TargetComponent"
	COMMAND_LONG_FIELD_CONFIRMATION     = "CommandLong.Confirmation"
)
View Source
const (
	COMMAND_ACK_FIELD_COMMAND = "CommandAck.Command"
	COMMAND_ACK_FIELD_RESULT  = "CommandAck.Result"
)
View Source
const (
	COMMAND_CANCEL_FIELD_COMMAND          = "CommandCancel.Command"
	COMMAND_CANCEL_FIELD_TARGET_SYSTEM    = "CommandCancel.TargetSystem"
	COMMAND_CANCEL_FIELD_TARGET_COMPONENT = "CommandCancel.TargetComponent"
)
View Source
const (
	MANUAL_SETPOINT_FIELD_TIME_BOOT_MS           = "ManualSetpoint.TimeBootMs"
	MANUAL_SETPOINT_FIELD_ROLL                   = "ManualSetpoint.Roll"
	MANUAL_SETPOINT_FIELD_PITCH                  = "ManualSetpoint.Pitch"
	MANUAL_SETPOINT_FIELD_YAW                    = "ManualSetpoint.Yaw"
	MANUAL_SETPOINT_FIELD_THRUST                 = "ManualSetpoint.Thrust"
	MANUAL_SETPOINT_FIELD_MODE_SWITCH            = "ManualSetpoint.ModeSwitch"
	MANUAL_SETPOINT_FIELD_MANUAL_OVERRIDE_SWITCH = "ManualSetpoint.ManualOverrideSwitch"
)
View Source
const (
	SET_ATTITUDE_TARGET_FIELD_TIME_BOOT_MS     = "SetAttitudeTarget.TimeBootMs"
	SET_ATTITUDE_TARGET_FIELD_Q                = "SetAttitudeTarget.Q"
	SET_ATTITUDE_TARGET_FIELD_BODY_ROLL_RATE   = "SetAttitudeTarget.BodyRollRate"
	SET_ATTITUDE_TARGET_FIELD_BODY_PITCH_RATE  = "SetAttitudeTarget.BodyPitchRate"
	SET_ATTITUDE_TARGET_FIELD_BODY_YAW_RATE    = "SetAttitudeTarget.BodyYawRate"
	SET_ATTITUDE_TARGET_FIELD_THRUST           = "SetAttitudeTarget.Thrust"
	SET_ATTITUDE_TARGET_FIELD_TARGET_SYSTEM    = "SetAttitudeTarget.TargetSystem"
	SET_ATTITUDE_TARGET_FIELD_TARGET_COMPONENT = "SetAttitudeTarget.TargetComponent"
	SET_ATTITUDE_TARGET_FIELD_TYPE_MASK        = "SetAttitudeTarget.TypeMask"
)
View Source
const (
	ATTITUDE_TARGET_FIELD_TIME_BOOT_MS    = "AttitudeTarget.TimeBootMs"
	ATTITUDE_TARGET_FIELD_Q               = "AttitudeTarget.Q"
	ATTITUDE_TARGET_FIELD_BODY_ROLL_RATE  = "AttitudeTarget.BodyRollRate"
	ATTITUDE_TARGET_FIELD_BODY_PITCH_RATE = "AttitudeTarget.BodyPitchRate"
	ATTITUDE_TARGET_FIELD_BODY_YAW_RATE   = "AttitudeTarget.BodyYawRate"
	ATTITUDE_TARGET_FIELD_THRUST          = "AttitudeTarget.Thrust"
	ATTITUDE_TARGET_FIELD_TYPE_MASK       = "AttitudeTarget.TypeMask"
)
View Source
const (
	SET_POSITION_TARGET_LOCAL_NED_FIELD_TIME_BOOT_MS     = "SetPositionTargetLocalNed.TimeBootMs"
	SET_POSITION_TARGET_LOCAL_NED_FIELD_X                = "SetPositionTargetLocalNed.X"
	SET_POSITION_TARGET_LOCAL_NED_FIELD_Y                = "SetPositionTargetLocalNed.Y"
	SET_POSITION_TARGET_LOCAL_NED_FIELD_Z                = "SetPositionTargetLocalNed.Z"
	SET_POSITION_TARGET_LOCAL_NED_FIELD_VX               = "SetPositionTargetLocalNed.Vx"
	SET_POSITION_TARGET_LOCAL_NED_FIELD_VY               = "SetPositionTargetLocalNed.Vy"
	SET_POSITION_TARGET_LOCAL_NED_FIELD_VZ               = "SetPositionTargetLocalNed.Vz"
	SET_POSITION_TARGET_LOCAL_NED_FIELD_AFX              = "SetPositionTargetLocalNed.Afx"
	SET_POSITION_TARGET_LOCAL_NED_FIELD_AFY              = "SetPositionTargetLocalNed.Afy"
	SET_POSITION_TARGET_LOCAL_NED_FIELD_AFZ              = "SetPositionTargetLocalNed.Afz"
	SET_POSITION_TARGET_LOCAL_NED_FIELD_YAW              = "SetPositionTargetLocalNed.Yaw"
	SET_POSITION_TARGET_LOCAL_NED_FIELD_YAW_RATE         = "SetPositionTargetLocalNed.YawRate"
	SET_POSITION_TARGET_LOCAL_NED_FIELD_TYPE_MASK        = "SetPositionTargetLocalNed.TypeMask"
	SET_POSITION_TARGET_LOCAL_NED_FIELD_TARGET_SYSTEM    = "SetPositionTargetLocalNed.TargetSystem"
	SET_POSITION_TARGET_LOCAL_NED_FIELD_TARGET_COMPONENT = "SetPositionTargetLocalNed.TargetComponent"
	SET_POSITION_TARGET_LOCAL_NED_FIELD_COORDINATE_FRAME = "SetPositionTargetLocalNed.CoordinateFrame"
)
View Source
const (
	POSITION_TARGET_LOCAL_NED_FIELD_TIME_BOOT_MS     = "PositionTargetLocalNed.TimeBootMs"
	POSITION_TARGET_LOCAL_NED_FIELD_X                = "PositionTargetLocalNed.X"
	POSITION_TARGET_LOCAL_NED_FIELD_Y                = "PositionTargetLocalNed.Y"
	POSITION_TARGET_LOCAL_NED_FIELD_Z                = "PositionTargetLocalNed.Z"
	POSITION_TARGET_LOCAL_NED_FIELD_VX               = "PositionTargetLocalNed.Vx"
	POSITION_TARGET_LOCAL_NED_FIELD_VY               = "PositionTargetLocalNed.Vy"
	POSITION_TARGET_LOCAL_NED_FIELD_VZ               = "PositionTargetLocalNed.Vz"
	POSITION_TARGET_LOCAL_NED_FIELD_AFX              = "PositionTargetLocalNed.Afx"
	POSITION_TARGET_LOCAL_NED_FIELD_AFY              = "PositionTargetLocalNed.Afy"
	POSITION_TARGET_LOCAL_NED_FIELD_AFZ              = "PositionTargetLocalNed.Afz"
	POSITION_TARGET_LOCAL_NED_FIELD_YAW              = "PositionTargetLocalNed.Yaw"
	POSITION_TARGET_LOCAL_NED_FIELD_YAW_RATE         = "PositionTargetLocalNed.YawRate"
	POSITION_TARGET_LOCAL_NED_FIELD_TYPE_MASK        = "PositionTargetLocalNed.TypeMask"
	POSITION_TARGET_LOCAL_NED_FIELD_COORDINATE_FRAME = "PositionTargetLocalNed.CoordinateFrame"
)
View Source
const (
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_TIME_BOOT_MS     = "SetPositionTargetGlobalInt.TimeBootMs"
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_LAT_INT          = "SetPositionTargetGlobalInt.LatInt"
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_LON_INT          = "SetPositionTargetGlobalInt.LonInt"
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_ALT              = "SetPositionTargetGlobalInt.Alt"
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_VX               = "SetPositionTargetGlobalInt.Vx"
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_VY               = "SetPositionTargetGlobalInt.Vy"
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_VZ               = "SetPositionTargetGlobalInt.Vz"
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_AFX              = "SetPositionTargetGlobalInt.Afx"
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_AFY              = "SetPositionTargetGlobalInt.Afy"
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_AFZ              = "SetPositionTargetGlobalInt.Afz"
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_YAW              = "SetPositionTargetGlobalInt.Yaw"
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_YAW_RATE         = "SetPositionTargetGlobalInt.YawRate"
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_TYPE_MASK        = "SetPositionTargetGlobalInt.TypeMask"
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_TARGET_SYSTEM    = "SetPositionTargetGlobalInt.TargetSystem"
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_TARGET_COMPONENT = "SetPositionTargetGlobalInt.TargetComponent"
	SET_POSITION_TARGET_GLOBAL_INT_FIELD_COORDINATE_FRAME = "SetPositionTargetGlobalInt.CoordinateFrame"
)
View Source
const (
	POSITION_TARGET_GLOBAL_INT_FIELD_TIME_BOOT_MS     = "PositionTargetGlobalInt.TimeBootMs"
	POSITION_TARGET_GLOBAL_INT_FIELD_LAT_INT          = "PositionTargetGlobalInt.LatInt"
	POSITION_TARGET_GLOBAL_INT_FIELD_LON_INT          = "PositionTargetGlobalInt.LonInt"
	POSITION_TARGET_GLOBAL_INT_FIELD_ALT              = "PositionTargetGlobalInt.Alt"
	POSITION_TARGET_GLOBAL_INT_FIELD_VX               = "PositionTargetGlobalInt.Vx"
	POSITION_TARGET_GLOBAL_INT_FIELD_VY               = "PositionTargetGlobalInt.Vy"
	POSITION_TARGET_GLOBAL_INT_FIELD_VZ               = "PositionTargetGlobalInt.Vz"
	POSITION_TARGET_GLOBAL_INT_FIELD_AFX              = "PositionTargetGlobalInt.Afx"
	POSITION_TARGET_GLOBAL_INT_FIELD_AFY              = "PositionTargetGlobalInt.Afy"
	POSITION_TARGET_GLOBAL_INT_FIELD_AFZ              = "PositionTargetGlobalInt.Afz"
	POSITION_TARGET_GLOBAL_INT_FIELD_YAW              = "PositionTargetGlobalInt.Yaw"
	POSITION_TARGET_GLOBAL_INT_FIELD_YAW_RATE         = "PositionTargetGlobalInt.YawRate"
	POSITION_TARGET_GLOBAL_INT_FIELD_TYPE_MASK        = "PositionTargetGlobalInt.TypeMask"
	POSITION_TARGET_GLOBAL_INT_FIELD_COORDINATE_FRAME = "PositionTargetGlobalInt.CoordinateFrame"
)
View Source
const (
	LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_FIELD_TIME_BOOT_MS = "LocalPositionNedSystemGlobalOffset.TimeBootMs"
	LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_FIELD_X            = "LocalPositionNedSystemGlobalOffset.X"
	LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_FIELD_Y            = "LocalPositionNedSystemGlobalOffset.Y"
	LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_FIELD_Z            = "LocalPositionNedSystemGlobalOffset.Z"
	LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_FIELD_ROLL         = "LocalPositionNedSystemGlobalOffset.Roll"
	LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_FIELD_PITCH        = "LocalPositionNedSystemGlobalOffset.Pitch"
	LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_FIELD_YAW          = "LocalPositionNedSystemGlobalOffset.Yaw"
)
View Source
const (
	HIL_STATE_FIELD_TIME_USEC  = "HilState.TimeUsec"
	HIL_STATE_FIELD_ROLL       = "HilState.Roll"
	HIL_STATE_FIELD_PITCH      = "HilState.Pitch"
	HIL_STATE_FIELD_YAW        = "HilState.Yaw"
	HIL_STATE_FIELD_ROLLSPEED  = "HilState.Rollspeed"
	HIL_STATE_FIELD_PITCHSPEED = "HilState.Pitchspeed"
	HIL_STATE_FIELD_YAWSPEED   = "HilState.Yawspeed"
	HIL_STATE_FIELD_LAT        = "HilState.Lat"
	HIL_STATE_FIELD_LON        = "HilState.Lon"
	HIL_STATE_FIELD_ALT        = "HilState.Alt"
	HIL_STATE_FIELD_VX         = "HilState.Vx"
	HIL_STATE_FIELD_VY         = "HilState.Vy"
	HIL_STATE_FIELD_VZ         = "HilState.Vz"
	HIL_STATE_FIELD_XACC       = "HilState.Xacc"
	HIL_STATE_FIELD_YACC       = "HilState.Yacc"
	HIL_STATE_FIELD_ZACC       = "HilState.Zacc"
)
View Source
const (
	HIL_CONTROLS_FIELD_TIME_USEC      = "HilControls.TimeUsec"
	HIL_CONTROLS_FIELD_ROLL_AILERONS  = "HilControls.RollAilerons"
	HIL_CONTROLS_FIELD_PITCH_ELEVATOR = "HilControls.PitchElevator"
	HIL_CONTROLS_FIELD_YAW_RUDDER     = "HilControls.YawRudder"
	HIL_CONTROLS_FIELD_THROTTLE       = "HilControls.Throttle"
	HIL_CONTROLS_FIELD_AUX1           = "HilControls.Aux1"
	HIL_CONTROLS_FIELD_AUX2           = "HilControls.Aux2"
	HIL_CONTROLS_FIELD_AUX3           = "HilControls.Aux3"
	HIL_CONTROLS_FIELD_AUX4           = "HilControls.Aux4"
	HIL_CONTROLS_FIELD_MODE           = "HilControls.Mode"
	HIL_CONTROLS_FIELD_NAV_MODE       = "HilControls.NavMode"
)
View Source
const (
	HIL_RC_INPUTS_RAW_FIELD_TIME_USEC  = "HilRcInputsRaw.TimeUsec"
	HIL_RC_INPUTS_RAW_FIELD_CHAN1_RAW  = "HilRcInputsRaw.Chan1Raw"
	HIL_RC_INPUTS_RAW_FIELD_CHAN2_RAW  = "HilRcInputsRaw.Chan2Raw"
	HIL_RC_INPUTS_RAW_FIELD_CHAN3_RAW  = "HilRcInputsRaw.Chan3Raw"
	HIL_RC_INPUTS_RAW_FIELD_CHAN4_RAW  = "HilRcInputsRaw.Chan4Raw"
	HIL_RC_INPUTS_RAW_FIELD_CHAN5_RAW  = "HilRcInputsRaw.Chan5Raw"
	HIL_RC_INPUTS_RAW_FIELD_CHAN6_RAW  = "HilRcInputsRaw.Chan6Raw"
	HIL_RC_INPUTS_RAW_FIELD_CHAN7_RAW  = "HilRcInputsRaw.Chan7Raw"
	HIL_RC_INPUTS_RAW_FIELD_CHAN8_RAW  = "HilRcInputsRaw.Chan8Raw"
	HIL_RC_INPUTS_RAW_FIELD_CHAN9_RAW  = "HilRcInputsRaw.Chan9Raw"
	HIL_RC_INPUTS_RAW_FIELD_CHAN10_RAW = "HilRcInputsRaw.Chan10Raw"
	HIL_RC_INPUTS_RAW_FIELD_CHAN11_RAW = "HilRcInputsRaw.Chan11Raw"
	HIL_RC_INPUTS_RAW_FIELD_CHAN12_RAW = "HilRcInputsRaw.Chan12Raw"
	HIL_RC_INPUTS_RAW_FIELD_RSSI       = "HilRcInputsRaw.Rssi"
)
View Source
const (
	HIL_ACTUATOR_CONTROLS_FIELD_TIME_USEC = "HilActuatorControls.TimeUsec"
	HIL_ACTUATOR_CONTROLS_FIELD_FLAGS     = "HilActuatorControls.Flags"
	HIL_ACTUATOR_CONTROLS_FIELD_CONTROLS  = "HilActuatorControls.Controls"
	HIL_ACTUATOR_CONTROLS_FIELD_MODE      = "HilActuatorControls.Mode"
)
View Source
const (
	OPTICAL_FLOW_FIELD_TIME_USEC       = "OpticalFlow.TimeUsec"
	OPTICAL_FLOW_FIELD_FLOW_COMP_M_X   = "OpticalFlow.FlowCompMX"
	OPTICAL_FLOW_FIELD_FLOW_COMP_M_Y   = "OpticalFlow.FlowCompMY"
	OPTICAL_FLOW_FIELD_GROUND_DISTANCE = "OpticalFlow.GroundDistance"
	OPTICAL_FLOW_FIELD_FLOW_X          = "OpticalFlow.FlowX"
	OPTICAL_FLOW_FIELD_FLOW_Y          = "OpticalFlow.FlowY"
	OPTICAL_FLOW_FIELD_SENSOR_ID       = "OpticalFlow.SensorID"
	OPTICAL_FLOW_FIELD_QUALITY         = "OpticalFlow.Quality"
)
View Source
const (
	GLOBAL_VISION_POSITION_ESTIMATE_FIELD_USEC  = "GlobalVisionPositionEstimate.Usec"
	GLOBAL_VISION_POSITION_ESTIMATE_FIELD_X     = "GlobalVisionPositionEstimate.X"
	GLOBAL_VISION_POSITION_ESTIMATE_FIELD_Y     = "GlobalVisionPositionEstimate.Y"
	GLOBAL_VISION_POSITION_ESTIMATE_FIELD_Z     = "GlobalVisionPositionEstimate.Z"
	GLOBAL_VISION_POSITION_ESTIMATE_FIELD_ROLL  = "GlobalVisionPositionEstimate.Roll"
	GLOBAL_VISION_POSITION_ESTIMATE_FIELD_PITCH = "GlobalVisionPositionEstimate.Pitch"
	GLOBAL_VISION_POSITION_ESTIMATE_FIELD_YAW   = "GlobalVisionPositionEstimate.Yaw"
)
View Source
const (
	VISION_POSITION_ESTIMATE_FIELD_USEC  = "VisionPositionEstimate.Usec"
	VISION_POSITION_ESTIMATE_FIELD_X     = "VisionPositionEstimate.X"
	VISION_POSITION_ESTIMATE_FIELD_Y     = "VisionPositionEstimate.Y"
	VISION_POSITION_ESTIMATE_FIELD_Z     = "VisionPositionEstimate.Z"
	VISION_POSITION_ESTIMATE_FIELD_ROLL  = "VisionPositionEstimate.Roll"
	VISION_POSITION_ESTIMATE_FIELD_PITCH = "VisionPositionEstimate.Pitch"
	VISION_POSITION_ESTIMATE_FIELD_YAW   = "VisionPositionEstimate.Yaw"
)
View Source
const (
	VISION_SPEED_ESTIMATE_FIELD_USEC = "VisionSpeedEstimate.Usec"
	VISION_SPEED_ESTIMATE_FIELD_X    = "VisionSpeedEstimate.X"
	VISION_SPEED_ESTIMATE_FIELD_Y    = "VisionSpeedEstimate.Y"
	VISION_SPEED_ESTIMATE_FIELD_Z    = "VisionSpeedEstimate.Z"
)
View Source
const (
	VICON_POSITION_ESTIMATE_FIELD_USEC  = "ViconPositionEstimate.Usec"
	VICON_POSITION_ESTIMATE_FIELD_X     = "ViconPositionEstimate.X"
	VICON_POSITION_ESTIMATE_FIELD_Y     = "ViconPositionEstimate.Y"
	VICON_POSITION_ESTIMATE_FIELD_Z     = "ViconPositionEstimate.Z"
	VICON_POSITION_ESTIMATE_FIELD_ROLL  = "ViconPositionEstimate.Roll"
	VICON_POSITION_ESTIMATE_FIELD_PITCH = "ViconPositionEstimate.Pitch"
	VICON_POSITION_ESTIMATE_FIELD_YAW   = "ViconPositionEstimate.Yaw"
)
View Source
const (
	HIGHRES_IMU_FIELD_TIME_USEC      = "HighresImu.TimeUsec"
	HIGHRES_IMU_FIELD_XACC           = "HighresImu.Xacc"
	HIGHRES_IMU_FIELD_YACC           = "HighresImu.Yacc"
	HIGHRES_IMU_FIELD_ZACC           = "HighresImu.Zacc"
	HIGHRES_IMU_FIELD_XGYRO          = "HighresImu.Xgyro"
	HIGHRES_IMU_FIELD_YGYRO          = "HighresImu.Ygyro"
	HIGHRES_IMU_FIELD_ZGYRO          = "HighresImu.Zgyro"
	HIGHRES_IMU_FIELD_XMAG           = "HighresImu.Xmag"
	HIGHRES_IMU_FIELD_YMAG           = "HighresImu.Ymag"
	HIGHRES_IMU_FIELD_ZMAG           = "HighresImu.Zmag"
	HIGHRES_IMU_FIELD_ABS_PRESSURE   = "HighresImu.AbsPressure"
	HIGHRES_IMU_FIELD_DIFF_PRESSURE  = "HighresImu.DiffPressure"
	HIGHRES_IMU_FIELD_PRESSURE_ALT   = "HighresImu.PressureAlt"
	HIGHRES_IMU_FIELD_TEMPERATURE    = "HighresImu.Temperature"
	HIGHRES_IMU_FIELD_FIELDS_UPDATED = "HighresImu.FieldsUpdated"
)
View Source
const (
	OPTICAL_FLOW_RAD_FIELD_TIME_USEC              = "OpticalFlowRad.TimeUsec"
	OPTICAL_FLOW_RAD_FIELD_INTEGRATION_TIME_US    = "OpticalFlowRad.IntegrationTimeUs"
	OPTICAL_FLOW_RAD_FIELD_INTEGRATED_X           = "OpticalFlowRad.IntegratedX"
	OPTICAL_FLOW_RAD_FIELD_INTEGRATED_Y           = "OpticalFlowRad.IntegratedY"
	OPTICAL_FLOW_RAD_FIELD_INTEGRATED_XGYRO       = "OpticalFlowRad.IntegratedXgyro"
	OPTICAL_FLOW_RAD_FIELD_INTEGRATED_YGYRO       = "OpticalFlowRad.IntegratedYgyro"
	OPTICAL_FLOW_RAD_FIELD_INTEGRATED_ZGYRO       = "OpticalFlowRad.IntegratedZgyro"
	OPTICAL_FLOW_RAD_FIELD_TIME_DELTA_DISTANCE_US = "OpticalFlowRad.TimeDeltaDistanceUs"
	OPTICAL_FLOW_RAD_FIELD_DISTANCE               = "OpticalFlowRad.Distance"
	OPTICAL_FLOW_RAD_FIELD_TEMPERATURE            = "OpticalFlowRad.Temperature"
	OPTICAL_FLOW_RAD_FIELD_SENSOR_ID              = "OpticalFlowRad.SensorID"
	OPTICAL_FLOW_RAD_FIELD_QUALITY                = "OpticalFlowRad.Quality"
)
View Source
const (
	HIL_SENSOR_FIELD_TIME_USEC      = "HilSensor.TimeUsec"
	HIL_SENSOR_FIELD_XACC           = "HilSensor.Xacc"
	HIL_SENSOR_FIELD_YACC           = "HilSensor.Yacc"
	HIL_SENSOR_FIELD_ZACC           = "HilSensor.Zacc"
	HIL_SENSOR_FIELD_XGYRO          = "HilSensor.Xgyro"
	HIL_SENSOR_FIELD_YGYRO          = "HilSensor.Ygyro"
	HIL_SENSOR_FIELD_ZGYRO          = "HilSensor.Zgyro"
	HIL_SENSOR_FIELD_XMAG           = "HilSensor.Xmag"
	HIL_SENSOR_FIELD_YMAG           = "HilSensor.Ymag"
	HIL_SENSOR_FIELD_ZMAG           = "HilSensor.Zmag"
	HIL_SENSOR_FIELD_ABS_PRESSURE   = "HilSensor.AbsPressure"
	HIL_SENSOR_FIELD_DIFF_PRESSURE  = "HilSensor.DiffPressure"
	HIL_SENSOR_FIELD_PRESSURE_ALT   = "HilSensor.PressureAlt"
	HIL_SENSOR_FIELD_TEMPERATURE    = "HilSensor.Temperature"
	HIL_SENSOR_FIELD_FIELDS_UPDATED = "HilSensor.FieldsUpdated"
)
View Source
const (
	SIM_STATE_FIELD_Q1           = "SimState.Q1"
	SIM_STATE_FIELD_Q2           = "SimState.Q2"
	SIM_STATE_FIELD_Q3           = "SimState.Q3"
	SIM_STATE_FIELD_Q4           = "SimState.Q4"
	SIM_STATE_FIELD_ROLL         = "SimState.Roll"
	SIM_STATE_FIELD_PITCH        = "SimState.Pitch"
	SIM_STATE_FIELD_YAW          = "SimState.Yaw"
	SIM_STATE_FIELD_XACC         = "SimState.Xacc"
	SIM_STATE_FIELD_YACC         = "SimState.Yacc"
	SIM_STATE_FIELD_ZACC         = "SimState.Zacc"
	SIM_STATE_FIELD_XGYRO        = "SimState.Xgyro"
	SIM_STATE_FIELD_YGYRO        = "SimState.Ygyro"
	SIM_STATE_FIELD_ZGYRO        = "SimState.Zgyro"
	SIM_STATE_FIELD_LAT          = "SimState.Lat"
	SIM_STATE_FIELD_LON          = "SimState.Lon"
	SIM_STATE_FIELD_ALT          = "SimState.Alt"
	SIM_STATE_FIELD_STD_DEV_HORZ = "SimState.StdDevHorz"
	SIM_STATE_FIELD_STD_DEV_VERT = "SimState.StdDevVert"
	SIM_STATE_FIELD_VN           = "SimState.Vn"
	SIM_STATE_FIELD_VE           = "SimState.Ve"
	SIM_STATE_FIELD_VD           = "SimState.Vd"
)
View Source
const (
	RADIO_STATUS_FIELD_RXERRORS = "RadioStatus.Rxerrors"
	RADIO_STATUS_FIELD_FIXED    = "RadioStatus.Fixed"
	RADIO_STATUS_FIELD_RSSI     = "RadioStatus.Rssi"
	RADIO_STATUS_FIELD_REMRSSI  = "RadioStatus.Remrssi"
	RADIO_STATUS_FIELD_TXBUF    = "RadioStatus.Txbuf"
	RADIO_STATUS_FIELD_NOISE    = "RadioStatus.Noise"
	RADIO_STATUS_FIELD_REMNOISE = "RadioStatus.Remnoise"
)
View Source
const (
	FILE_TRANSFER_PROTOCOL_FIELD_TARGET_NETWORK   = "FileTransferProtocol.TargetNetwork"
	FILE_TRANSFER_PROTOCOL_FIELD_TARGET_SYSTEM    = "FileTransferProtocol.TargetSystem"
	FILE_TRANSFER_PROTOCOL_FIELD_TARGET_COMPONENT = "FileTransferProtocol.TargetComponent"
	FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD          = "FileTransferProtocol.Payload"
)
View Source
const (
	TIMESYNC_FIELD_TC1 = "Timesync.Tc1"
	TIMESYNC_FIELD_TS1 = "Timesync.Ts1"
)
View Source
const (
	CAMERA_TRIGGER_FIELD_TIME_USEC = "CameraTrigger.TimeUsec"
	CAMERA_TRIGGER_FIELD_SEQ       = "CameraTrigger.Seq"
)
View Source
const (
	HIL_GPS_FIELD_TIME_USEC          = "HilGps.TimeUsec"
	HIL_GPS_FIELD_LAT                = "HilGps.Lat"
	HIL_GPS_FIELD_LON                = "HilGps.Lon"
	HIL_GPS_FIELD_ALT                = "HilGps.Alt"
	HIL_GPS_FIELD_EPH                = "HilGps.Eph"
	HIL_GPS_FIELD_EPV                = "HilGps.Epv"
	HIL_GPS_FIELD_VEL                = "HilGps.Vel"
	HIL_GPS_FIELD_VN                 = "HilGps.Vn"
	HIL_GPS_FIELD_VE                 = "HilGps.Ve"
	HIL_GPS_FIELD_VD                 = "HilGps.Vd"
	HIL_GPS_FIELD_COG                = "HilGps.Cog"
	HIL_GPS_FIELD_FIX_TYPE           = "HilGps.FixType"
	HIL_GPS_FIELD_SATELLITES_VISIBLE = "HilGps.SatellitesVisible"
)
View Source
const (
	HIL_OPTICAL_FLOW_FIELD_TIME_USEC              = "HilOpticalFlow.TimeUsec"
	HIL_OPTICAL_FLOW_FIELD_INTEGRATION_TIME_US    = "HilOpticalFlow.IntegrationTimeUs"
	HIL_OPTICAL_FLOW_FIELD_INTEGRATED_X           = "HilOpticalFlow.IntegratedX"
	HIL_OPTICAL_FLOW_FIELD_INTEGRATED_Y           = "HilOpticalFlow.IntegratedY"
	HIL_OPTICAL_FLOW_FIELD_INTEGRATED_XGYRO       = "HilOpticalFlow.IntegratedXgyro"
	HIL_OPTICAL_FLOW_FIELD_INTEGRATED_YGYRO       = "HilOpticalFlow.IntegratedYgyro"
	HIL_OPTICAL_FLOW_FIELD_INTEGRATED_ZGYRO       = "HilOpticalFlow.IntegratedZgyro"
	HIL_OPTICAL_FLOW_FIELD_TIME_DELTA_DISTANCE_US = "HilOpticalFlow.TimeDeltaDistanceUs"
	HIL_OPTICAL_FLOW_FIELD_DISTANCE               = "HilOpticalFlow.Distance"
	HIL_OPTICAL_FLOW_FIELD_TEMPERATURE            = "HilOpticalFlow.Temperature"
	HIL_OPTICAL_FLOW_FIELD_SENSOR_ID              = "HilOpticalFlow.SensorID"
	HIL_OPTICAL_FLOW_FIELD_QUALITY                = "HilOpticalFlow.Quality"
)
View Source
const (
	HIL_STATE_QUATERNION_FIELD_TIME_USEC           = "HilStateQuaternion.TimeUsec"
	HIL_STATE_QUATERNION_FIELD_ATTITUDE_QUATERNION = "HilStateQuaternion.AttitudeQuaternion"
	HIL_STATE_QUATERNION_FIELD_ROLLSPEED           = "HilStateQuaternion.Rollspeed"
	HIL_STATE_QUATERNION_FIELD_PITCHSPEED          = "HilStateQuaternion.Pitchspeed"
	HIL_STATE_QUATERNION_FIELD_YAWSPEED            = "HilStateQuaternion.Yawspeed"
	HIL_STATE_QUATERNION_FIELD_LAT                 = "HilStateQuaternion.Lat"
	HIL_STATE_QUATERNION_FIELD_LON                 = "HilStateQuaternion.Lon"
	HIL_STATE_QUATERNION_FIELD_ALT                 = "HilStateQuaternion.Alt"
	HIL_STATE_QUATERNION_FIELD_VX                  = "HilStateQuaternion.Vx"
	HIL_STATE_QUATERNION_FIELD_VY                  = "HilStateQuaternion.Vy"
	HIL_STATE_QUATERNION_FIELD_VZ                  = "HilStateQuaternion.Vz"
	HIL_STATE_QUATERNION_FIELD_IND_AIRSPEED        = "HilStateQuaternion.IndAirspeed"
	HIL_STATE_QUATERNION_FIELD_TRUE_AIRSPEED       = "HilStateQuaternion.TrueAirspeed"
	HIL_STATE_QUATERNION_FIELD_XACC                = "HilStateQuaternion.Xacc"
	HIL_STATE_QUATERNION_FIELD_YACC                = "HilStateQuaternion.Yacc"
	HIL_STATE_QUATERNION_FIELD_ZACC                = "HilStateQuaternion.Zacc"
)
View Source
const (
	SCALED_IMU2_FIELD_TIME_BOOT_MS = "ScaledImu2.TimeBootMs"
	SCALED_IMU2_FIELD_XACC         = "ScaledImu2.Xacc"
	SCALED_IMU2_FIELD_YACC         = "ScaledImu2.Yacc"
	SCALED_IMU2_FIELD_ZACC         = "ScaledImu2.Zacc"
	SCALED_IMU2_FIELD_XGYRO        = "ScaledImu2.Xgyro"
	SCALED_IMU2_FIELD_YGYRO        = "ScaledImu2.Ygyro"
	SCALED_IMU2_FIELD_ZGYRO        = "ScaledImu2.Zgyro"
	SCALED_IMU2_FIELD_XMAG         = "ScaledImu2.Xmag"
	SCALED_IMU2_FIELD_YMAG         = "ScaledImu2.Ymag"
	SCALED_IMU2_FIELD_ZMAG         = "ScaledImu2.Zmag"
)
View Source
const (
	LOG_REQUEST_LIST_FIELD_START            = "LogRequestList.Start"
	LOG_REQUEST_LIST_FIELD_END              = "LogRequestList.End"
	LOG_REQUEST_LIST_FIELD_TARGET_SYSTEM    = "LogRequestList.TargetSystem"
	LOG_REQUEST_LIST_FIELD_TARGET_COMPONENT = "LogRequestList.TargetComponent"
)
View Source
const (
	LOG_ENTRY_FIELD_TIME_UTC     = "LogEntry.TimeUtc"
	LOG_ENTRY_FIELD_SIZE         = "LogEntry.Size"
	LOG_ENTRY_FIELD_ID           = "LogEntry.ID"
	LOG_ENTRY_FIELD_NUM_LOGS     = "LogEntry.NumLogs"
	LOG_ENTRY_FIELD_LAST_LOG_NUM = "LogEntry.LastLogNum"
)
View Source
const (
	LOG_REQUEST_DATA_FIELD_OFS              = "LogRequestData.Ofs"
	LOG_REQUEST_DATA_FIELD_COUNT            = "LogRequestData.Count"
	LOG_REQUEST_DATA_FIELD_ID               = "LogRequestData.ID"
	LOG_REQUEST_DATA_FIELD_TARGET_SYSTEM    = "LogRequestData.TargetSystem"
	LOG_REQUEST_DATA_FIELD_TARGET_COMPONENT = "LogRequestData.TargetComponent"
)
View Source
const (
	LOG_DATA_FIELD_OFS   = "LogData.Ofs"
	LOG_DATA_FIELD_ID    = "LogData.ID"
	LOG_DATA_FIELD_COUNT = "LogData.Count"
	LOG_DATA_FIELD_DATA  = "LogData.Data"
)
View Source
const (
	LOG_ERASE_FIELD_TARGET_SYSTEM    = "LogErase.TargetSystem"
	LOG_ERASE_FIELD_TARGET_COMPONENT = "LogErase.TargetComponent"
)
View Source
const (
	LOG_REQUEST_END_FIELD_TARGET_SYSTEM    = "LogRequestEnd.TargetSystem"
	LOG_REQUEST_END_FIELD_TARGET_COMPONENT = "LogRequestEnd.TargetComponent"
)
View Source
const (
	GPS_INJECT_DATA_FIELD_TARGET_SYSTEM    = "GpsInjectData.TargetSystem"
	GPS_INJECT_DATA_FIELD_TARGET_COMPONENT = "GpsInjectData.TargetComponent"
	GPS_INJECT_DATA_FIELD_LEN              = "GpsInjectData.Len"
	GPS_INJECT_DATA_FIELD_DATA             = "GpsInjectData.Data"
)
View Source
const (
	GPS2_RAW_FIELD_TIME_USEC          = "Gps2Raw.TimeUsec"
	GPS2_RAW_FIELD_LAT                = "Gps2Raw.Lat"
	GPS2_RAW_FIELD_LON                = "Gps2Raw.Lon"
	GPS2_RAW_FIELD_ALT                = "Gps2Raw.Alt"
	GPS2_RAW_FIELD_DGPS_AGE           = "Gps2Raw.DgpsAge"
	GPS2_RAW_FIELD_EPH                = "Gps2Raw.Eph"
	GPS2_RAW_FIELD_EPV                = "Gps2Raw.Epv"
	GPS2_RAW_FIELD_VEL                = "Gps2Raw.Vel"
	GPS2_RAW_FIELD_COG                = "Gps2Raw.Cog"
	GPS2_RAW_FIELD_FIX_TYPE           = "Gps2Raw.FixType"
	GPS2_RAW_FIELD_SATELLITES_VISIBLE = "Gps2Raw.SatellitesVisible"
	GPS2_RAW_FIELD_DGPS_NUMCH         = "Gps2Raw.DgpsNumch"
)
View Source
const (
	POWER_STATUS_FIELD_VCC    = "PowerStatus.Vcc"
	POWER_STATUS_FIELD_VSERVO = "PowerStatus.Vservo"
	POWER_STATUS_FIELD_FLAGS  = "PowerStatus.Flags"
)
View Source
const (
	SERIAL_CONTROL_FIELD_BAUDRATE = "SerialControl.Baudrate"
	SERIAL_CONTROL_FIELD_TIMEOUT  = "SerialControl.Timeout"
	SERIAL_CONTROL_FIELD_DEVICE   = "SerialControl.Device"
	SERIAL_CONTROL_FIELD_FLAGS    = "SerialControl.Flags"
	SERIAL_CONTROL_FIELD_COUNT    = "SerialControl.Count"
	SERIAL_CONTROL_FIELD_DATA     = "SerialControl.Data"
)
View Source
const (
	GPS_RTK_FIELD_TIME_LAST_BASELINE_MS = "GpsRtk.TimeLastBaselineMs"
	GPS_RTK_FIELD_TOW                   = "GpsRtk.Tow"
	GPS_RTK_FIELD_BASELINE_A_MM         = "GpsRtk.BaselineAMm"
	GPS_RTK_FIELD_BASELINE_B_MM         = "GpsRtk.BaselineBMm"
	GPS_RTK_FIELD_BASELINE_C_MM         = "GpsRtk.BaselineCMm"
	GPS_RTK_FIELD_ACCURACY              = "GpsRtk.Accuracy"
	GPS_RTK_FIELD_IAR_NUM_HYPOTHESES    = "GpsRtk.IarNumHypotheses"
	GPS_RTK_FIELD_WN                    = "GpsRtk.Wn"
	GPS_RTK_FIELD_RTK_RECEIVER_ID       = "GpsRtk.RtkReceiverID"
	GPS_RTK_FIELD_RTK_HEALTH            = "GpsRtk.RtkHealth"
	GPS_RTK_FIELD_RTK_RATE              = "GpsRtk.RtkRate"
	GPS_RTK_FIELD_NSATS                 = "GpsRtk.Nsats"
	GPS_RTK_FIELD_BASELINE_COORDS_TYPE  = "GpsRtk.BaselineCoordsType"
)
View Source
const (
	GPS2_RTK_FIELD_TIME_LAST_BASELINE_MS = "Gps2Rtk.TimeLastBaselineMs"
	GPS2_RTK_FIELD_TOW                   = "Gps2Rtk.Tow"
	GPS2_RTK_FIELD_BASELINE_A_MM         = "Gps2Rtk.BaselineAMm"
	GPS2_RTK_FIELD_BASELINE_B_MM         = "Gps2Rtk.BaselineBMm"
	GPS2_RTK_FIELD_BASELINE_C_MM         = "Gps2Rtk.BaselineCMm"
	GPS2_RTK_FIELD_ACCURACY              = "Gps2Rtk.Accuracy"
	GPS2_RTK_FIELD_IAR_NUM_HYPOTHESES    = "Gps2Rtk.IarNumHypotheses"
	GPS2_RTK_FIELD_WN                    = "Gps2Rtk.Wn"
	GPS2_RTK_FIELD_RTK_RECEIVER_ID       = "Gps2Rtk.RtkReceiverID"
	GPS2_RTK_FIELD_RTK_HEALTH            = "Gps2Rtk.RtkHealth"
	GPS2_RTK_FIELD_RTK_RATE              = "Gps2Rtk.RtkRate"
	GPS2_RTK_FIELD_NSATS                 = "Gps2Rtk.Nsats"
	GPS2_RTK_FIELD_BASELINE_COORDS_TYPE  = "Gps2Rtk.BaselineCoordsType"
)
View Source
const (
	SCALED_IMU3_FIELD_TIME_BOOT_MS = "ScaledImu3.TimeBootMs"
	SCALED_IMU3_FIELD_XACC         = "ScaledImu3.Xacc"
	SCALED_IMU3_FIELD_YACC         = "ScaledImu3.Yacc"
	SCALED_IMU3_FIELD_ZACC         = "ScaledImu3.Zacc"
	SCALED_IMU3_FIELD_XGYRO        = "ScaledImu3.Xgyro"
	SCALED_IMU3_FIELD_YGYRO        = "ScaledImu3.Ygyro"
	SCALED_IMU3_FIELD_ZGYRO        = "ScaledImu3.Zgyro"
	SCALED_IMU3_FIELD_XMAG         = "ScaledImu3.Xmag"
	SCALED_IMU3_FIELD_YMAG         = "ScaledImu3.Ymag"
	SCALED_IMU3_FIELD_ZMAG         = "ScaledImu3.Zmag"
)
View Source
const (
	DATA_TRANSMISSION_HANDSHAKE_FIELD_SIZE        = "DataTransmissionHandshake.Size"
	DATA_TRANSMISSION_HANDSHAKE_FIELD_WIDTH       = "DataTransmissionHandshake.Width"
	DATA_TRANSMISSION_HANDSHAKE_FIELD_HEIGHT      = "DataTransmissionHandshake.Height"
	DATA_TRANSMISSION_HANDSHAKE_FIELD_PACKETS     = "DataTransmissionHandshake.Packets"
	DATA_TRANSMISSION_HANDSHAKE_FIELD_TYPE        = "DataTransmissionHandshake.Type"
	DATA_TRANSMISSION_HANDSHAKE_FIELD_PAYLOAD     = "DataTransmissionHandshake.Payload"
	DATA_TRANSMISSION_HANDSHAKE_FIELD_JPG_QUALITY = "DataTransmissionHandshake.JpgQuality"
)
View Source
const (
	ENCAPSULATED_DATA_FIELD_SEQNR = "EncapsulatedData.Seqnr"
	ENCAPSULATED_DATA_FIELD_DATA  = "EncapsulatedData.Data"
)
View Source
const (
	DISTANCE_SENSOR_FIELD_TIME_BOOT_MS     = "DistanceSensor.TimeBootMs"
	DISTANCE_SENSOR_FIELD_MIN_DISTANCE     = "DistanceSensor.MinDistance"
	DISTANCE_SENSOR_FIELD_MAX_DISTANCE     = "DistanceSensor.MaxDistance"
	DISTANCE_SENSOR_FIELD_CURRENT_DISTANCE = "DistanceSensor.CurrentDistance"
	DISTANCE_SENSOR_FIELD_TYPE             = "DistanceSensor.Type"
	DISTANCE_SENSOR_FIELD_ID               = "DistanceSensor.ID"
	DISTANCE_SENSOR_FIELD_ORIENTATION      = "DistanceSensor.Orientation"
	DISTANCE_SENSOR_FIELD_COVARIANCE       = "DistanceSensor.Covariance"
)
View Source
const (
	TERRAIN_REQUEST_FIELD_MASK         = "TerrainRequest.Mask"
	TERRAIN_REQUEST_FIELD_LAT          = "TerrainRequest.Lat"
	TERRAIN_REQUEST_FIELD_LON          = "TerrainRequest.Lon"
	TERRAIN_REQUEST_FIELD_GRID_SPACING = "TerrainRequest.GridSpacing"
)
View Source
const (
	TERRAIN_DATA_FIELD_LAT          = "TerrainData.Lat"
	TERRAIN_DATA_FIELD_LON          = "TerrainData.Lon"
	TERRAIN_DATA_FIELD_GRID_SPACING = "TerrainData.GridSpacing"
	TERRAIN_DATA_FIELD_DATA         = "TerrainData.Data"
	TERRAIN_DATA_FIELD_GRIDBIT      = "TerrainData.Gridbit"
)
View Source
const (
	TERRAIN_CHECK_FIELD_LAT = "TerrainCheck.Lat"
	TERRAIN_CHECK_FIELD_LON = "TerrainCheck.Lon"
)
View Source
const (
	TERRAIN_REPORT_FIELD_LAT            = "TerrainReport.Lat"
	TERRAIN_REPORT_FIELD_LON            = "TerrainReport.Lon"
	TERRAIN_REPORT_FIELD_TERRAIN_HEIGHT = "TerrainReport.TerrainHeight"
	TERRAIN_REPORT_FIELD_CURRENT_HEIGHT = "TerrainReport.CurrentHeight"
	TERRAIN_REPORT_FIELD_SPACING        = "TerrainReport.Spacing"
	TERRAIN_REPORT_FIELD_PENDING        = "TerrainReport.Pending"
	TERRAIN_REPORT_FIELD_LOADED         = "TerrainReport.Loaded"
)
View Source
const (
	SCALED_PRESSURE2_FIELD_TIME_BOOT_MS = "ScaledPressure2.TimeBootMs"
	SCALED_PRESSURE2_FIELD_PRESS_ABS    = "ScaledPressure2.PressAbs"
	SCALED_PRESSURE2_FIELD_PRESS_DIFF   = "ScaledPressure2.PressDiff"
	SCALED_PRESSURE2_FIELD_TEMPERATURE  = "ScaledPressure2.Temperature"
)
View Source
const (
	ATT_POS_MOCAP_FIELD_TIME_USEC = "AttPosMocap.TimeUsec"
	ATT_POS_MOCAP_FIELD_Q         = "AttPosMocap.Q"
	ATT_POS_MOCAP_FIELD_X         = "AttPosMocap.X"
	ATT_POS_MOCAP_FIELD_Y         = "AttPosMocap.Y"
	ATT_POS_MOCAP_FIELD_Z         = "AttPosMocap.Z"
)
View Source
const (
	SET_ACTUATOR_CONTROL_TARGET_FIELD_TIME_USEC        = "SetActuatorControlTarget.TimeUsec"
	SET_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS         = "SetActuatorControlTarget.Controls"
	SET_ACTUATOR_CONTROL_TARGET_FIELD_GROUP_MLX        = "SetActuatorControlTarget.GroupMlx"
	SET_ACTUATOR_CONTROL_TARGET_FIELD_TARGET_SYSTEM    = "SetActuatorControlTarget.TargetSystem"
	SET_ACTUATOR_CONTROL_TARGET_FIELD_TARGET_COMPONENT = "SetActuatorControlTarget.TargetComponent"
)
View Source
const (
	ACTUATOR_CONTROL_TARGET_FIELD_TIME_USEC = "ActuatorControlTarget.TimeUsec"
	ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS  = "ActuatorControlTarget.Controls"
	ACTUATOR_CONTROL_TARGET_FIELD_GROUP_MLX = "ActuatorControlTarget.GroupMlx"
)
View Source
const (
	ALTITUDE_FIELD_TIME_USEC          = "Altitude.TimeUsec"
	ALTITUDE_FIELD_ALTITUDE_MONOTONIC = "Altitude.AltitudeMonotonic"
	ALTITUDE_FIELD_ALTITUDE_AMSL      = "Altitude.AltitudeAmsl"
	ALTITUDE_FIELD_ALTITUDE_LOCAL     = "Altitude.AltitudeLocal"
	ALTITUDE_FIELD_ALTITUDE_RELATIVE  = "Altitude.AltitudeRelative"
	ALTITUDE_FIELD_ALTITUDE_TERRAIN   = "Altitude.AltitudeTerrain"
	ALTITUDE_FIELD_BOTTOM_CLEARANCE   = "Altitude.BottomClearance"
)
View Source
const (
	RESOURCE_REQUEST_FIELD_REQUEST_ID    = "ResourceRequest.RequestID"
	RESOURCE_REQUEST_FIELD_URI_TYPE      = "ResourceRequest.URIType"
	RESOURCE_REQUEST_FIELD_URI           = "ResourceRequest.URI"
	RESOURCE_REQUEST_FIELD_TRANSFER_TYPE = "ResourceRequest.TransferType"
	RESOURCE_REQUEST_FIELD_STORAGE       = "ResourceRequest.Storage"
)
View Source
const (
	SCALED_PRESSURE3_FIELD_TIME_BOOT_MS = "ScaledPressure3.TimeBootMs"
	SCALED_PRESSURE3_FIELD_PRESS_ABS    = "ScaledPressure3.PressAbs"
	SCALED_PRESSURE3_FIELD_PRESS_DIFF   = "ScaledPressure3.PressDiff"
	SCALED_PRESSURE3_FIELD_TEMPERATURE  = "ScaledPressure3.Temperature"
)
View Source
const (
	FOLLOW_TARGET_FIELD_TIMESTAMP        = "FollowTarget.Timestamp"
	FOLLOW_TARGET_FIELD_CUSTOM_STATE     = "FollowTarget.CustomState"
	FOLLOW_TARGET_FIELD_LAT              = "FollowTarget.Lat"
	FOLLOW_TARGET_FIELD_LON              = "FollowTarget.Lon"
	FOLLOW_TARGET_FIELD_ALT              = "FollowTarget.Alt"
	FOLLOW_TARGET_FIELD_VEL              = "FollowTarget.Vel"
	FOLLOW_TARGET_FIELD_ACC              = "FollowTarget.Acc"
	FOLLOW_TARGET_FIELD_ATTITUDE_Q       = "FollowTarget.AttitudeQ"
	FOLLOW_TARGET_FIELD_RATES            = "FollowTarget.Rates"
	FOLLOW_TARGET_FIELD_POSITION_COV     = "FollowTarget.PositionCov"
	FOLLOW_TARGET_FIELD_EST_CAPABILITIES = "FollowTarget.EstCapabilities"
)
View Source
const (
	CONTROL_SYSTEM_STATE_FIELD_TIME_USEC    = "ControlSystemState.TimeUsec"
	CONTROL_SYSTEM_STATE_FIELD_X_ACC        = "ControlSystemState.XAcc"
	CONTROL_SYSTEM_STATE_FIELD_Y_ACC        = "ControlSystemState.YAcc"
	CONTROL_SYSTEM_STATE_FIELD_Z_ACC        = "ControlSystemState.ZAcc"
	CONTROL_SYSTEM_STATE_FIELD_X_VEL        = "ControlSystemState.XVel"
	CONTROL_SYSTEM_STATE_FIELD_Y_VEL        = "ControlSystemState.YVel"
	CONTROL_SYSTEM_STATE_FIELD_Z_VEL        = "ControlSystemState.ZVel"
	CONTROL_SYSTEM_STATE_FIELD_X_POS        = "ControlSystemState.XPos"
	CONTROL_SYSTEM_STATE_FIELD_Y_POS        = "ControlSystemState.YPos"
	CONTROL_SYSTEM_STATE_FIELD_Z_POS        = "ControlSystemState.ZPos"
	CONTROL_SYSTEM_STATE_FIELD_AIRSPEED     = "ControlSystemState.Airspeed"
	CONTROL_SYSTEM_STATE_FIELD_VEL_VARIANCE = "ControlSystemState.VelVariance"
	CONTROL_SYSTEM_STATE_FIELD_POS_VARIANCE = "ControlSystemState.PosVariance"
	CONTROL_SYSTEM_STATE_FIELD_Q            = "ControlSystemState.Q"
	CONTROL_SYSTEM_STATE_FIELD_ROLL_RATE    = "ControlSystemState.RollRate"
	CONTROL_SYSTEM_STATE_FIELD_PITCH_RATE   = "ControlSystemState.PitchRate"
	CONTROL_SYSTEM_STATE_FIELD_YAW_RATE     = "ControlSystemState.YawRate"
)
View Source
const (
	BATTERY_STATUS_FIELD_CURRENT_CONSUMED  = "BatteryStatus.CurrentConsumed"
	BATTERY_STATUS_FIELD_ENERGY_CONSUMED   = "BatteryStatus.EnergyConsumed"
	BATTERY_STATUS_FIELD_TEMPERATURE       = "BatteryStatus.Temperature"
	BATTERY_STATUS_FIELD_VOLTAGES          = "BatteryStatus.Voltages"
	BATTERY_STATUS_FIELD_CURRENT_BATTERY   = "BatteryStatus.CurrentBattery"
	BATTERY_STATUS_FIELD_ID                = "BatteryStatus.ID"
	BATTERY_STATUS_FIELD_BATTERY_FUNCTION  = "BatteryStatus.BatteryFunction"
	BATTERY_STATUS_FIELD_TYPE              = "BatteryStatus.Type"
	BATTERY_STATUS_FIELD_BATTERY_REMAINING = "BatteryStatus.BatteryRemaining"
)
View Source
const (
	AUTOPILOT_VERSION_FIELD_CAPABILITIES              = "AutopilotVersion.Capabilities"
	AUTOPILOT_VERSION_FIELD_UID                       = "AutopilotVersion.UID"
	AUTOPILOT_VERSION_FIELD_FLIGHT_SW_VERSION         = "AutopilotVersion.FlightSwVersion"
	AUTOPILOT_VERSION_FIELD_MIDDLEWARE_SW_VERSION     = "AutopilotVersion.MiddlewareSwVersion"
	AUTOPILOT_VERSION_FIELD_OS_SW_VERSION             = "AutopilotVersion.OsSwVersion"
	AUTOPILOT_VERSION_FIELD_BOARD_VERSION             = "AutopilotVersion.BoardVersion"
	AUTOPILOT_VERSION_FIELD_VENDOR_ID                 = "AutopilotVersion.VendorID"
	AUTOPILOT_VERSION_FIELD_PRODUCT_ID                = "AutopilotVersion.ProductID"
	AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION     = "AutopilotVersion.FlightCustomVersion"
	AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION = "AutopilotVersion.MiddlewareCustomVersion"
	AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION         = "AutopilotVersion.OsCustomVersion"
)
View Source
const (
	LANDING_TARGET_FIELD_TIME_USEC  = "LandingTarget.TimeUsec"
	LANDING_TARGET_FIELD_ANGLE_X    = "LandingTarget.AngleX"
	LANDING_TARGET_FIELD_ANGLE_Y    = "LandingTarget.AngleY"
	LANDING_TARGET_FIELD_DISTANCE   = "LandingTarget.Distance"
	LANDING_TARGET_FIELD_SIZE_X     = "LandingTarget.SizeX"
	LANDING_TARGET_FIELD_SIZE_Y     = "LandingTarget.SizeY"
	LANDING_TARGET_FIELD_TARGET_NUM = "LandingTarget.TargetNum"
	LANDING_TARGET_FIELD_FRAME      = "LandingTarget.Frame"
)
View Source
const (
	FENCE_STATUS_FIELD_BREACH_TIME   = "FenceStatus.BreachTime"
	FENCE_STATUS_FIELD_BREACH_COUNT  = "FenceStatus.BreachCount"
	FENCE_STATUS_FIELD_BREACH_STATUS = "FenceStatus.BreachStatus"
	FENCE_STATUS_FIELD_BREACH_TYPE   = "FenceStatus.BreachType"
)
View Source
const (
	MAG_CAL_REPORT_FIELD_FITNESS    = "MagCalReport.Fitness"
	MAG_CAL_REPORT_FIELD_OFS_X      = "MagCalReport.OfsX"
	MAG_CAL_REPORT_FIELD_OFS_Y      = "MagCalReport.OfsY"
	MAG_CAL_REPORT_FIELD_OFS_Z      = "MagCalReport.OfsZ"
	MAG_CAL_REPORT_FIELD_DIAG_X     = "MagCalReport.DiagX"
	MAG_CAL_REPORT_FIELD_DIAG_Y     = "MagCalReport.DiagY"
	MAG_CAL_REPORT_FIELD_DIAG_Z     = "MagCalReport.DiagZ"
	MAG_CAL_REPORT_FIELD_OFFDIAG_X  = "MagCalReport.OffdiagX"
	MAG_CAL_REPORT_FIELD_OFFDIAG_Y  = "MagCalReport.OffdiagY"
	MAG_CAL_REPORT_FIELD_OFFDIAG_Z  = "MagCalReport.OffdiagZ"
	MAG_CAL_REPORT_FIELD_COMPASS_ID = "MagCalReport.CompassID"
	MAG_CAL_REPORT_FIELD_CAL_MASK   = "MagCalReport.CalMask"
	MAG_CAL_REPORT_FIELD_CAL_STATUS = "MagCalReport.CalStatus"
	MAG_CAL_REPORT_FIELD_AUTOSAVED  = "MagCalReport.Autosaved"
)
View Source
const (
	EFI_STATUS_FIELD_ECU_INDEX                   = "EfiStatus.EcuIndex"
	EFI_STATUS_FIELD_RPM                         = "EfiStatus.Rpm"
	EFI_STATUS_FIELD_FUEL_CONSUMED               = "EfiStatus.FuelConsumed"
	EFI_STATUS_FIELD_FUEL_FLOW                   = "EfiStatus.FuelFlow"
	EFI_STATUS_FIELD_ENGINE_LOAD                 = "EfiStatus.EngineLoad"
	EFI_STATUS_FIELD_THROTTLE_POSITION           = "EfiStatus.ThrottlePosition"
	EFI_STATUS_FIELD_SPARK_DWELL_TIME            = "EfiStatus.SparkDwellTime"
	EFI_STATUS_FIELD_BAROMETRIC_PRESSURE         = "EfiStatus.BarometricPressure"
	EFI_STATUS_FIELD_INTAKE_MANIFOLD_PRESSURE    = "EfiStatus.IntakeManifoldPressure"
	EFI_STATUS_FIELD_INTAKE_MANIFOLD_TEMPERATURE = "EfiStatus.IntakeManifoldTemperature"
	EFI_STATUS_FIELD_CYLINDER_HEAD_TEMPERATURE   = "EfiStatus.CylinderHeadTemperature"
	EFI_STATUS_FIELD_IGNITION_TIMING             = "EfiStatus.IgnitionTiming"
	EFI_STATUS_FIELD_INJECTION_TIME              = "EfiStatus.InjectionTime"
	EFI_STATUS_FIELD_EXHAUST_GAS_TEMPERATURE     = "EfiStatus.ExhaustGasTemperature"
	EFI_STATUS_FIELD_THROTTLE_OUT                = "EfiStatus.ThrottleOut"
	EFI_STATUS_FIELD_PT_COMPENSATION             = "EfiStatus.PtCompensation"
	EFI_STATUS_FIELD_HEALTH                      = "EfiStatus.Health"
)
View Source
const (
	ESTIMATOR_STATUS_FIELD_TIME_USEC          = "EstimatorStatus.TimeUsec"
	ESTIMATOR_STATUS_FIELD_VEL_RATIO          = "EstimatorStatus.VelRatio"
	ESTIMATOR_STATUS_FIELD_POS_HORIZ_RATIO    = "EstimatorStatus.PosHorizRatio"
	ESTIMATOR_STATUS_FIELD_POS_VERT_RATIO     = "EstimatorStatus.PosVertRatio"
	ESTIMATOR_STATUS_FIELD_MAG_RATIO          = "EstimatorStatus.MagRatio"
	ESTIMATOR_STATUS_FIELD_HAGL_RATIO         = "EstimatorStatus.HaglRatio"
	ESTIMATOR_STATUS_FIELD_TAS_RATIO          = "EstimatorStatus.TasRatio"
	ESTIMATOR_STATUS_FIELD_POS_HORIZ_ACCURACY = "EstimatorStatus.PosHorizAccuracy"
	ESTIMATOR_STATUS_FIELD_POS_VERT_ACCURACY  = "EstimatorStatus.PosVertAccuracy"
	ESTIMATOR_STATUS_FIELD_FLAGS              = "EstimatorStatus.Flags"
)
View Source
const (
	WIND_COV_FIELD_TIME_USEC      = "WindCov.TimeUsec"
	WIND_COV_FIELD_WIND_X         = "WindCov.WindX"
	WIND_COV_FIELD_WIND_Y         = "WindCov.WindY"
	WIND_COV_FIELD_WIND_Z         = "WindCov.WindZ"
	WIND_COV_FIELD_VAR_HORIZ      = "WindCov.VarHoriz"
	WIND_COV_FIELD_VAR_VERT       = "WindCov.VarVert"
	WIND_COV_FIELD_WIND_ALT       = "WindCov.WindAlt"
	WIND_COV_FIELD_HORIZ_ACCURACY = "WindCov.HorizAccuracy"
	WIND_COV_FIELD_VERT_ACCURACY  = "WindCov.VertAccuracy"
)
View Source
const (
	GPS_INPUT_FIELD_TIME_USEC          = "GpsInput.TimeUsec"
	GPS_INPUT_FIELD_TIME_WEEK_MS       = "GpsInput.TimeWeekMs"
	GPS_INPUT_FIELD_LAT                = "GpsInput.Lat"
	GPS_INPUT_FIELD_LON                = "GpsInput.Lon"
	GPS_INPUT_FIELD_ALT                = "GpsInput.Alt"
	GPS_INPUT_FIELD_HDOP               = "GpsInput.Hdop"
	GPS_INPUT_FIELD_VDOP               = "GpsInput.Vdop"
	GPS_INPUT_FIELD_VN                 = "GpsInput.Vn"
	GPS_INPUT_FIELD_VE                 = "GpsInput.Ve"
	GPS_INPUT_FIELD_VD                 = "GpsInput.Vd"
	GPS_INPUT_FIELD_SPEED_ACCURACY     = "GpsInput.SpeedAccuracy"
	GPS_INPUT_FIELD_HORIZ_ACCURACY     = "GpsInput.HorizAccuracy"
	GPS_INPUT_FIELD_VERT_ACCURACY      = "GpsInput.VertAccuracy"
	GPS_INPUT_FIELD_IGNORE_FLAGS       = "GpsInput.IgnoreFlags"
	GPS_INPUT_FIELD_TIME_WEEK          = "GpsInput.TimeWeek"
	GPS_INPUT_FIELD_GPS_ID             = "GpsInput.GpsID"
	GPS_INPUT_FIELD_FIX_TYPE           = "GpsInput.FixType"
	GPS_INPUT_FIELD_SATELLITES_VISIBLE = "GpsInput.SatellitesVisible"
)
View Source
const (
	GPS_RTCM_DATA_FIELD_FLAGS = "GpsRtcmData.Flags"
	GPS_RTCM_DATA_FIELD_LEN   = "GpsRtcmData.Len"
	GPS_RTCM_DATA_FIELD_DATA  = "GpsRtcmData.Data"
)
View Source
const (
	HIGH_LATENCY_FIELD_CUSTOM_MODE       = "HighLatency.CustomMode"
	HIGH_LATENCY_FIELD_LATITUDE          = "HighLatency.Latitude"
	HIGH_LATENCY_FIELD_LONGITUDE         = "HighLatency.Longitude"
	HIGH_LATENCY_FIELD_ROLL              = "HighLatency.Roll"
	HIGH_LATENCY_FIELD_PITCH             = "HighLatency.Pitch"
	HIGH_LATENCY_FIELD_HEADING           = "HighLatency.Heading"
	HIGH_LATENCY_FIELD_HEADING_SP        = "HighLatency.HeadingSp"
	HIGH_LATENCY_FIELD_ALTITUDE_AMSL     = "HighLatency.AltitudeAmsl"
	HIGH_LATENCY_FIELD_ALTITUDE_SP       = "HighLatency.AltitudeSp"
	HIGH_LATENCY_FIELD_WP_DISTANCE       = "HighLatency.WpDistance"
	HIGH_LATENCY_FIELD_BASE_MODE         = "HighLatency.BaseMode"
	HIGH_LATENCY_FIELD_LANDED_STATE      = "HighLatency.LandedState"
	HIGH_LATENCY_FIELD_THROTTLE          = "HighLatency.Throttle"
	HIGH_LATENCY_FIELD_AIRSPEED          = "HighLatency.Airspeed"
	HIGH_LATENCY_FIELD_AIRSPEED_SP       = "HighLatency.AirspeedSp"
	HIGH_LATENCY_FIELD_GROUNDSPEED       = "HighLatency.Groundspeed"
	HIGH_LATENCY_FIELD_CLIMB_RATE        = "HighLatency.ClimbRate"
	HIGH_LATENCY_FIELD_GPS_NSAT          = "HighLatency.GpsNsat"
	HIGH_LATENCY_FIELD_GPS_FIX_TYPE      = "HighLatency.GpsFixType"
	HIGH_LATENCY_FIELD_BATTERY_REMAINING = "HighLatency.BatteryRemaining"
	HIGH_LATENCY_FIELD_TEMPERATURE       = "HighLatency.Temperature"
	HIGH_LATENCY_FIELD_TEMPERATURE_AIR   = "HighLatency.TemperatureAir"
	HIGH_LATENCY_FIELD_FAILSAFE          = "HighLatency.Failsafe"
	HIGH_LATENCY_FIELD_WP_NUM            = "HighLatency.WpNum"
)
View Source
const (
	HIGH_LATENCY2_FIELD_TIMESTAMP       = "HighLatency2.Timestamp"
	HIGH_LATENCY2_FIELD_LATITUDE        = "HighLatency2.Latitude"
	HIGH_LATENCY2_FIELD_LONGITUDE       = "HighLatency2.Longitude"
	HIGH_LATENCY2_FIELD_CUSTOM_MODE     = "HighLatency2.CustomMode"
	HIGH_LATENCY2_FIELD_ALTITUDE        = "HighLatency2.Altitude"
	HIGH_LATENCY2_FIELD_TARGET_ALTITUDE = "HighLatency2.TargetAltitude"
	HIGH_LATENCY2_FIELD_TARGET_DISTANCE = "HighLatency2.TargetDistance"
	HIGH_LATENCY2_FIELD_WP_NUM          = "HighLatency2.WpNum"
	HIGH_LATENCY2_FIELD_FAILURE_FLAGS   = "HighLatency2.FailureFlags"
	HIGH_LATENCY2_FIELD_TYPE            = "HighLatency2.Type"
	HIGH_LATENCY2_FIELD_AUTOPILOT       = "HighLatency2.Autopilot"
	HIGH_LATENCY2_FIELD_HEADING         = "HighLatency2.Heading"
	HIGH_LATENCY2_FIELD_TARGET_HEADING  = "HighLatency2.TargetHeading"
	HIGH_LATENCY2_FIELD_THROTTLE        = "HighLatency2.Throttle"
	HIGH_LATENCY2_FIELD_AIRSPEED        = "HighLatency2.Airspeed"
	HIGH_LATENCY2_FIELD_AIRSPEED_SP     = "HighLatency2.AirspeedSp"
	HIGH_LATENCY2_FIELD_GROUNDSPEED     = "HighLatency2.Groundspeed"
	HIGH_LATENCY2_FIELD_WINDSPEED       = "HighLatency2.Windspeed"
	HIGH_LATENCY2_FIELD_WIND_HEADING    = "HighLatency2.WindHeading"
	HIGH_LATENCY2_FIELD_EPH             = "HighLatency2.Eph"
	HIGH_LATENCY2_FIELD_EPV             = "HighLatency2.Epv"
	HIGH_LATENCY2_FIELD_TEMPERATURE_AIR = "HighLatency2.TemperatureAir"
	HIGH_LATENCY2_FIELD_CLIMB_RATE      = "HighLatency2.ClimbRate"
	HIGH_LATENCY2_FIELD_BATTERY         = "HighLatency2.Battery"
	HIGH_LATENCY2_FIELD_CUSTOM0         = "HighLatency2.Custom0"
	HIGH_LATENCY2_FIELD_CUSTOM1         = "HighLatency2.Custom1"
	HIGH_LATENCY2_FIELD_CUSTOM2         = "HighLatency2.Custom2"
)
View Source
const (
	VIBRATION_FIELD_TIME_USEC   = "Vibration.TimeUsec"
	VIBRATION_FIELD_VIBRATION_X = "Vibration.VibrationX"
	VIBRATION_FIELD_VIBRATION_Y = "Vibration.VibrationY"
	VIBRATION_FIELD_VIBRATION_Z = "Vibration.VibrationZ"
	VIBRATION_FIELD_CLIPPING_0  = "Vibration.Clipping0"
	VIBRATION_FIELD_CLIPPING_1  = "Vibration.Clipping1"
	VIBRATION_FIELD_CLIPPING_2  = "Vibration.Clipping2"
)
View Source
const (
	HOME_POSITION_FIELD_LATITUDE   = "HomePosition.Latitude"
	HOME_POSITION_FIELD_LONGITUDE  = "HomePosition.Longitude"
	HOME_POSITION_FIELD_ALTITUDE   = "HomePosition.Altitude"
	HOME_POSITION_FIELD_X          = "HomePosition.X"
	HOME_POSITION_FIELD_Y          = "HomePosition.Y"
	HOME_POSITION_FIELD_Z          = "HomePosition.Z"
	HOME_POSITION_FIELD_Q          = "HomePosition.Q"
	HOME_POSITION_FIELD_APPROACH_X = "HomePosition.ApproachX"
	HOME_POSITION_FIELD_APPROACH_Y = "HomePosition.ApproachY"
	HOME_POSITION_FIELD_APPROACH_Z = "HomePosition.ApproachZ"
)
View Source
const (
	SET_HOME_POSITION_FIELD_LATITUDE      = "SetHomePosition.Latitude"
	SET_HOME_POSITION_FIELD_LONGITUDE     = "SetHomePosition.Longitude"
	SET_HOME_POSITION_FIELD_ALTITUDE      = "SetHomePosition.Altitude"
	SET_HOME_POSITION_FIELD_X             = "SetHomePosition.X"
	SET_HOME_POSITION_FIELD_Y             = "SetHomePosition.Y"
	SET_HOME_POSITION_FIELD_Z             = "SetHomePosition.Z"
	SET_HOME_POSITION_FIELD_Q             = "SetHomePosition.Q"
	SET_HOME_POSITION_FIELD_APPROACH_X    = "SetHomePosition.ApproachX"
	SET_HOME_POSITION_FIELD_APPROACH_Y    = "SetHomePosition.ApproachY"
	SET_HOME_POSITION_FIELD_APPROACH_Z    = "SetHomePosition.ApproachZ"
	SET_HOME_POSITION_FIELD_TARGET_SYSTEM = "SetHomePosition.TargetSystem"
)
View Source
const (
	MESSAGE_INTERVAL_FIELD_INTERVAL_US = "MessageInterval.IntervalUs"
	MESSAGE_INTERVAL_FIELD_MESSAGE_ID  = "MessageInterval.MessageID"
)
View Source
const (
	EXTENDED_SYS_STATE_FIELD_VTOL_STATE   = "ExtendedSysState.VtolState"
	EXTENDED_SYS_STATE_FIELD_LANDED_STATE = "ExtendedSysState.LandedState"
)
View Source
const (
	ADSB_VEHICLE_FIELD_ICAO_ADDRESS  = "AdsbVehicle.IcaoAddress"
	ADSB_VEHICLE_FIELD_LAT           = "AdsbVehicle.Lat"
	ADSB_VEHICLE_FIELD_LON           = "AdsbVehicle.Lon"
	ADSB_VEHICLE_FIELD_ALTITUDE      = "AdsbVehicle.Altitude"
	ADSB_VEHICLE_FIELD_HEADING       = "AdsbVehicle.Heading"
	ADSB_VEHICLE_FIELD_HOR_VELOCITY  = "AdsbVehicle.HorVelocity"
	ADSB_VEHICLE_FIELD_VER_VELOCITY  = "AdsbVehicle.VerVelocity"
	ADSB_VEHICLE_FIELD_FLAGS         = "AdsbVehicle.Flags"
	ADSB_VEHICLE_FIELD_SQUAWK        = "AdsbVehicle.Squawk"
	ADSB_VEHICLE_FIELD_ALTITUDE_TYPE = "AdsbVehicle.AltitudeType"
	ADSB_VEHICLE_FIELD_CALLSIGN      = "AdsbVehicle.Callsign"
	ADSB_VEHICLE_FIELD_EMITTER_TYPE  = "AdsbVehicle.EmitterType"
	ADSB_VEHICLE_FIELD_TSLC          = "AdsbVehicle.Tslc"
)
View Source
const (
	COLLISION_FIELD_ID                       = "Collision.ID"
	COLLISION_FIELD_TIME_TO_MINIMUM_DELTA    = "Collision.TimeToMinimumDelta"
	COLLISION_FIELD_ALTITUDE_MINIMUM_DELTA   = "Collision.AltitudeMinimumDelta"
	COLLISION_FIELD_HORIZONTAL_MINIMUM_DELTA = "Collision.HorizontalMinimumDelta"
	COLLISION_FIELD_SRC                      = "Collision.Src"
	COLLISION_FIELD_ACTION                   = "Collision.Action"
	COLLISION_FIELD_THREAT_LEVEL             = "Collision.ThreatLevel"
)
View Source
const (
	V2_EXTENSION_FIELD_MESSAGE_TYPE     = "V2Extension.MessageType"
	V2_EXTENSION_FIELD_TARGET_NETWORK   = "V2Extension.TargetNetwork"
	V2_EXTENSION_FIELD_TARGET_SYSTEM    = "V2Extension.TargetSystem"
	V2_EXTENSION_FIELD_TARGET_COMPONENT = "V2Extension.TargetComponent"
	V2_EXTENSION_FIELD_PAYLOAD          = "V2Extension.Payload"
)
View Source
const (
	MEMORY_VECT_FIELD_ADDRESS = "MemoryVect.Address"
	MEMORY_VECT_FIELD_VER     = "MemoryVect.Ver"
	MEMORY_VECT_FIELD_TYPE    = "MemoryVect.Type"
	MEMORY_VECT_FIELD_VALUE   = "MemoryVect.Value"
)
View Source
const (
	DEBUG_VECT_FIELD_TIME_USEC = "DebugVect.TimeUsec"
	DEBUG_VECT_FIELD_X         = "DebugVect.X"
	DEBUG_VECT_FIELD_Y         = "DebugVect.Y"
	DEBUG_VECT_FIELD_Z         = "DebugVect.Z"
	DEBUG_VECT_FIELD_NAME      = "DebugVect.Name"
)
View Source
const (
	NAMED_VALUE_FLOAT_FIELD_TIME_BOOT_MS = "NamedValueFloat.TimeBootMs"
	NAMED_VALUE_FLOAT_FIELD_VALUE        = "NamedValueFloat.Value"
	NAMED_VALUE_FLOAT_FIELD_NAME         = "NamedValueFloat.Name"
)
View Source
const (
	NAMED_VALUE_INT_FIELD_TIME_BOOT_MS = "NamedValueInt.TimeBootMs"
	NAMED_VALUE_INT_FIELD_VALUE        = "NamedValueInt.Value"
	NAMED_VALUE_INT_FIELD_NAME         = "NamedValueInt.Name"
)
View Source
const (
	STATUSTEXT_FIELD_SEVERITY = "Statustext.Severity"
	STATUSTEXT_FIELD_TEXT     = "Statustext.Text"
)
View Source
const (
	DEBUG_FIELD_TIME_BOOT_MS = "Debug.TimeBootMs"
	DEBUG_FIELD_VALUE        = "Debug.Value"
	DEBUG_FIELD_IND          = "Debug.Ind"
)
View Source
const (
	HEARTBEAT_FIELD_CUSTOM_MODE     = "Heartbeat.CustomMode"
	HEARTBEAT_FIELD_TYPE            = "Heartbeat.Type"
	HEARTBEAT_FIELD_AUTOPILOT       = "Heartbeat.Autopilot"
	HEARTBEAT_FIELD_BASE_MODE       = "Heartbeat.BaseMode"
	HEARTBEAT_FIELD_SYSTEM_STATUS   = "Heartbeat.SystemStatus"
	HEARTBEAT_FIELD_MAVLINK_VERSION = "Heartbeat.MavlinkVersion"
)
View Source
const (
	NAV_FILTER_BIAS_FIELD_USEC    = "NavFilterBias.Usec"
	NAV_FILTER_BIAS_FIELD_ACCEL_0 = "NavFilterBias.Accel0"
	NAV_FILTER_BIAS_FIELD_ACCEL_1 = "NavFilterBias.Accel1"
	NAV_FILTER_BIAS_FIELD_ACCEL_2 = "NavFilterBias.Accel2"
	NAV_FILTER_BIAS_FIELD_GYRO_0  = "NavFilterBias.Gyro0"
	NAV_FILTER_BIAS_FIELD_GYRO_1  = "NavFilterBias.Gyro1"
	NAV_FILTER_BIAS_FIELD_GYRO_2  = "NavFilterBias.Gyro2"
)
View Source
const (
	RADIO_CALIBRATION_FIELD_AILERON  = "RadioCalibration.Aileron"
	RADIO_CALIBRATION_FIELD_ELEVATOR = "RadioCalibration.Elevator"
	RADIO_CALIBRATION_FIELD_RUDDER   = "RadioCalibration.Rudder"
	RADIO_CALIBRATION_FIELD_GYRO     = "RadioCalibration.Gyro"
	RADIO_CALIBRATION_FIELD_PITCH    = "RadioCalibration.Pitch"
	RADIO_CALIBRATION_FIELD_THROTTLE = "RadioCalibration.Throttle"
)
View Source
const (
	UALBERTA_SYS_STATUS_FIELD_MODE     = "UalbertaSysStatus.Mode"
	UALBERTA_SYS_STATUS_FIELD_NAV_MODE = "UalbertaSysStatus.NavMode"
	UALBERTA_SYS_STATUS_FIELD_PILOT    = "UalbertaSysStatus.Pilot"
)
View Source
const (
	MSG_ID_SENSOR_OFFSETS                          message.MessageID = 150
	MSG_ID_SET_MAG_OFFSETS                         message.MessageID = 151
	MSG_ID_MEMINFO                                 message.MessageID = 152
	MSG_ID_AP_ADC                                  message.MessageID = 153
	MSG_ID_DIGICAM_CONFIGURE                       message.MessageID = 154
	MSG_ID_DIGICAM_CONTROL                         message.MessageID = 155
	MSG_ID_MOUNT_CONFIGURE                         message.MessageID = 156
	MSG_ID_MOUNT_CONTROL                           message.MessageID = 157
	MSG_ID_MOUNT_STATUS                            message.MessageID = 158
	MSG_ID_FENCE_POINT                             message.MessageID = 160
	MSG_ID_FENCE_FETCH_POINT                       message.MessageID = 161
	MSG_ID_AHRS                                    message.MessageID = 163
	MSG_ID_SIMSTATE                                message.MessageID = 164
	MSG_ID_HWSTATUS                                message.MessageID = 165
	MSG_ID_RADIO                                   message.MessageID = 166
	MSG_ID_LIMITS_STATUS                           message.MessageID = 167
	MSG_ID_WIND                                    message.MessageID = 168
	MSG_ID_DATA16                                  message.MessageID = 169
	MSG_ID_DATA32                                  message.MessageID = 170
	MSG_ID_DATA64                                  message.MessageID = 171
	MSG_ID_DATA96                                  message.MessageID = 172
	MSG_ID_RANGEFINDER                             message.MessageID = 173
	MSG_ID_AIRSPEED_AUTOCAL                        message.MessageID = 174
	MSG_ID_RALLY_POINT                             message.MessageID = 175
	MSG_ID_RALLY_FETCH_POINT                       message.MessageID = 176
	MSG_ID_COMPASSMOT_STATUS                       message.MessageID = 177
	MSG_ID_AHRS2                                   message.MessageID = 178
	MSG_ID_CAMERA_STATUS                           message.MessageID = 179
	MSG_ID_CAMERA_FEEDBACK                         message.MessageID = 180
	MSG_ID_BATTERY2                                message.MessageID = 181
	MSG_ID_AHRS3                                   message.MessageID = 182
	MSG_ID_AUTOPILOT_VERSION_REQUEST               message.MessageID = 183
	MSG_ID_REMOTE_LOG_DATA_BLOCK                   message.MessageID = 184
	MSG_ID_REMOTE_LOG_BLOCK_STATUS                 message.MessageID = 185
	MSG_ID_LED_CONTROL                             message.MessageID = 186
	MSG_ID_MAG_CAL_PROGRESS                        message.MessageID = 191
	MSG_ID_EKF_STATUS_REPORT                       message.MessageID = 193
	MSG_ID_PID_TUNING                              message.MessageID = 194
	MSG_ID_DEEPSTALL                               message.MessageID = 195
	MSG_ID_GIMBAL_REPORT                           message.MessageID = 200
	MSG_ID_GIMBAL_CONTROL                          message.MessageID = 201
	MSG_ID_GIMBAL_TORQUE_CMD_REPORT                message.MessageID = 214
	MSG_ID_GOPRO_HEARTBEAT                         message.MessageID = 215
	MSG_ID_GOPRO_GET_REQUEST                       message.MessageID = 216
	MSG_ID_GOPRO_GET_RESPONSE                      message.MessageID = 217
	MSG_ID_GOPRO_SET_REQUEST                       message.MessageID = 218
	MSG_ID_GOPRO_SET_RESPONSE                      message.MessageID = 219
	MSG_ID_RPM                                     message.MessageID = 226
	MSG_ID_SYS_STATUS                              message.MessageID = 1
	MSG_ID_SYSTEM_TIME                             message.MessageID = 2
	MSG_ID_PING                                    message.MessageID = 4
	MSG_ID_CHANGE_OPERATOR_CONTROL                 message.MessageID = 5
	MSG_ID_CHANGE_OPERATOR_CONTROL_ACK             message.MessageID = 6
	MSG_ID_AUTH_KEY                                message.MessageID = 7
	MSG_ID_LINK_NODE_STATUS                        message.MessageID = 8
	MSG_ID_SET_MODE                                message.MessageID = 11
	MSG_ID_PARAM_ACK_TRANSACTION                   message.MessageID = 19
	MSG_ID_PARAM_REQUEST_READ                      message.MessageID = 20
	MSG_ID_PARAM_REQUEST_LIST                      message.MessageID = 21
	MSG_ID_PARAM_VALUE                             message.MessageID = 22
	MSG_ID_PARAM_SET                               message.MessageID = 23
	MSG_ID_GPS_RAW_INT                             message.MessageID = 24
	MSG_ID_GPS_STATUS                              message.MessageID = 25
	MSG_ID_SCALED_IMU                              message.MessageID = 26
	MSG_ID_RAW_IMU                                 message.MessageID = 27
	MSG_ID_RAW_PRESSURE                            message.MessageID = 28
	MSG_ID_SCALED_PRESSURE                         message.MessageID = 29
	MSG_ID_ATTITUDE                                message.MessageID = 30
	MSG_ID_ATTITUDE_QUATERNION                     message.MessageID = 31
	MSG_ID_LOCAL_POSITION_NED                      message.MessageID = 32
	MSG_ID_GLOBAL_POSITION_INT                     message.MessageID = 33
	MSG_ID_RC_CHANNELS_SCALED                      message.MessageID = 34
	MSG_ID_RC_CHANNELS_RAW                         message.MessageID = 35
	MSG_ID_SERVO_OUTPUT_RAW                        message.MessageID = 36
	MSG_ID_MISSION_REQUEST_PARTIAL_LIST            message.MessageID = 37
	MSG_ID_MISSION_WRITE_PARTIAL_LIST              message.MessageID = 38
	MSG_ID_MISSION_ITEM                            message.MessageID = 39
	MSG_ID_MISSION_REQUEST                         message.MessageID = 40
	MSG_ID_MISSION_SET_CURRENT                     message.MessageID = 41
	MSG_ID_MISSION_CURRENT                         message.MessageID = 42
	MSG_ID_MISSION_REQUEST_LIST                    message.MessageID = 43
	MSG_ID_MISSION_COUNT                           message.MessageID = 44
	MSG_ID_MISSION_CLEAR_ALL                       message.MessageID = 45
	MSG_ID_MISSION_ITEM_REACHED                    message.MessageID = 46
	MSG_ID_MISSION_ACK                             message.MessageID = 47
	MSG_ID_SET_GPS_GLOBAL_ORIGIN                   message.MessageID = 48
	MSG_ID_GPS_GLOBAL_ORIGIN                       message.MessageID = 49
	MSG_ID_PARAM_MAP_RC                            message.MessageID = 50
	MSG_ID_MISSION_REQUEST_INT                     message.MessageID = 51
	MSG_ID_MISSION_CHANGED                         message.MessageID = 52
	MSG_ID_SAFETY_SET_ALLOWED_AREA                 message.MessageID = 54
	MSG_ID_SAFETY_ALLOWED_AREA                     message.MessageID = 55
	MSG_ID_ATTITUDE_QUATERNION_COV                 message.MessageID = 61
	MSG_ID_NAV_CONTROLLER_OUTPUT                   message.MessageID = 62
	MSG_ID_GLOBAL_POSITION_INT_COV                 message.MessageID = 63
	MSG_ID_LOCAL_POSITION_NED_COV                  message.MessageID = 64
	MSG_ID_RC_CHANNELS                             message.MessageID = 65
	MSG_ID_REQUEST_DATA_STREAM                     message.MessageID = 66
	MSG_ID_DATA_STREAM                             message.MessageID = 67
	MSG_ID_MANUAL_CONTROL                          message.MessageID = 69
	MSG_ID_RC_CHANNELS_OVERRIDE                    message.MessageID = 70
	MSG_ID_MISSION_ITEM_INT                        message.MessageID = 73
	MSG_ID_VFR_HUD                                 message.MessageID = 74
	MSG_ID_COMMAND_INT                             message.MessageID = 75
	MSG_ID_COMMAND_LONG                            message.MessageID = 76
	MSG_ID_COMMAND_ACK                             message.MessageID = 77
	MSG_ID_COMMAND_CANCEL                          message.MessageID = 80
	MSG_ID_MANUAL_SETPOINT                         message.MessageID = 81
	MSG_ID_SET_ATTITUDE_TARGET                     message.MessageID = 82
	MSG_ID_ATTITUDE_TARGET                         message.MessageID = 83
	MSG_ID_SET_POSITION_TARGET_LOCAL_NED           message.MessageID = 84
	MSG_ID_POSITION_TARGET_LOCAL_NED               message.MessageID = 85
	MSG_ID_SET_POSITION_TARGET_GLOBAL_INT          message.MessageID = 86
	MSG_ID_POSITION_TARGET_GLOBAL_INT              message.MessageID = 87
	MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET message.MessageID = 89
	MSG_ID_HIL_STATE                               message.MessageID = 90
	MSG_ID_HIL_CONTROLS                            message.MessageID = 91
	MSG_ID_HIL_RC_INPUTS_RAW                       message.MessageID = 92
	MSG_ID_HIL_ACTUATOR_CONTROLS                   message.MessageID = 93
	MSG_ID_OPTICAL_FLOW                            message.MessageID = 100
	MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE         message.MessageID = 101
	MSG_ID_VISION_POSITION_ESTIMATE                message.MessageID = 102
	MSG_ID_VISION_SPEED_ESTIMATE                   message.MessageID = 103
	MSG_ID_VICON_POSITION_ESTIMATE                 message.MessageID = 104
	MSG_ID_HIGHRES_IMU                             message.MessageID = 105
	MSG_ID_OPTICAL_FLOW_RAD                        message.MessageID = 106
	MSG_ID_HIL_SENSOR                              message.MessageID = 107
	MSG_ID_SIM_STATE                               message.MessageID = 108
	MSG_ID_RADIO_STATUS                            message.MessageID = 109
	MSG_ID_FILE_TRANSFER_PROTOCOL                  message.MessageID = 110
	MSG_ID_TIMESYNC                                message.MessageID = 111
	MSG_ID_CAMERA_TRIGGER                          message.MessageID = 112
	MSG_ID_HIL_GPS                                 message.MessageID = 113
	MSG_ID_HIL_OPTICAL_FLOW                        message.MessageID = 114
	MSG_ID_HIL_STATE_QUATERNION                    message.MessageID = 115
	MSG_ID_SCALED_IMU2                             message.MessageID = 116
	MSG_ID_LOG_REQUEST_LIST                        message.MessageID = 117
	MSG_ID_LOG_ENTRY                               message.MessageID = 118
	MSG_ID_LOG_REQUEST_DATA                        message.MessageID = 119
	MSG_ID_LOG_DATA                                message.MessageID = 120
	MSG_ID_LOG_ERASE                               message.MessageID = 121
	MSG_ID_LOG_REQUEST_END                         message.MessageID = 122
	MSG_ID_GPS_INJECT_DATA                         message.MessageID = 123
	MSG_ID_GPS2_RAW                                message.MessageID = 124
	MSG_ID_POWER_STATUS                            message.MessageID = 125
	MSG_ID_SERIAL_CONTROL                          message.MessageID = 126
	MSG_ID_GPS_RTK                                 message.MessageID = 127
	MSG_ID_GPS2_RTK                                message.MessageID = 128
	MSG_ID_SCALED_IMU3                             message.MessageID = 129
	MSG_ID_DATA_TRANSMISSION_HANDSHAKE             message.MessageID = 130
	MSG_ID_ENCAPSULATED_DATA                       message.MessageID = 131
	MSG_ID_DISTANCE_SENSOR                         message.MessageID = 132
	MSG_ID_TERRAIN_REQUEST                         message.MessageID = 133
	MSG_ID_TERRAIN_DATA                            message.MessageID = 134
	MSG_ID_TERRAIN_CHECK                           message.MessageID = 135
	MSG_ID_TERRAIN_REPORT                          message.MessageID = 136
	MSG_ID_SCALED_PRESSURE2                        message.MessageID = 137
	MSG_ID_ATT_POS_MOCAP                           message.MessageID = 138
	MSG_ID_SET_ACTUATOR_CONTROL_TARGET             message.MessageID = 139
	MSG_ID_ACTUATOR_CONTROL_TARGET                 message.MessageID = 140
	MSG_ID_ALTITUDE                                message.MessageID = 141
	MSG_ID_RESOURCE_REQUEST                        message.MessageID = 142
	MSG_ID_SCALED_PRESSURE3                        message.MessageID = 143
	MSG_ID_FOLLOW_TARGET                           message.MessageID = 144
	MSG_ID_CONTROL_SYSTEM_STATE                    message.MessageID = 146
	MSG_ID_BATTERY_STATUS                          message.MessageID = 147
	MSG_ID_AUTOPILOT_VERSION                       message.MessageID = 148
	MSG_ID_LANDING_TARGET                          message.MessageID = 149
	MSG_ID_FENCE_STATUS                            message.MessageID = 162
	MSG_ID_MAG_CAL_REPORT                          message.MessageID = 192
	MSG_ID_EFI_STATUS                              message.MessageID = 225
	MSG_ID_ESTIMATOR_STATUS                        message.MessageID = 230
	MSG_ID_WIND_COV                                message.MessageID = 231
	MSG_ID_GPS_INPUT                               message.MessageID = 232
	MSG_ID_GPS_RTCM_DATA                           message.MessageID = 233
	MSG_ID_HIGH_LATENCY                            message.MessageID = 234
	MSG_ID_HIGH_LATENCY2                           message.MessageID = 235
	MSG_ID_VIBRATION                               message.MessageID = 241
	MSG_ID_HOME_POSITION                           message.MessageID = 242
	MSG_ID_SET_HOME_POSITION                       message.MessageID = 243
	MSG_ID_MESSAGE_INTERVAL                        message.MessageID = 244
	MSG_ID_EXTENDED_SYS_STATE                      message.MessageID = 245
	MSG_ID_ADSB_VEHICLE                            message.MessageID = 246
	MSG_ID_COLLISION                               message.MessageID = 247
	MSG_ID_V2_EXTENSION                            message.MessageID = 248
	MSG_ID_MEMORY_VECT                             message.MessageID = 249
	MSG_ID_DEBUG_VECT                              message.MessageID = 250
	MSG_ID_NAMED_VALUE_FLOAT                       message.MessageID = 251
	MSG_ID_NAMED_VALUE_INT                         message.MessageID = 252
	MSG_ID_STATUSTEXT                              message.MessageID = 253
	MSG_ID_DEBUG                                   message.MessageID = 254
	MSG_ID_HEARTBEAT                               message.MessageID = 0
	MSG_ID_NAV_FILTER_BIAS                         message.MessageID = 220
	MSG_ID_RADIO_CALIBRATION                       message.MessageID = 221
	MSG_ID_UALBERTA_SYS_STATUS                     message.MessageID = 222
)

Message IDs

View Source
const (
	AUTH_KEY_FIELD_KEY = "AuthKey.Key"
)
View Source
const (
	MISSION_CURRENT_FIELD_SEQ = "MissionCurrent.Seq"
)
View Source
const (
	MISSION_ITEM_REACHED_FIELD_SEQ = "MissionItemReached.Seq"
)
View Source
const (
	// Version of mavgen which generate this code or user defined (by mavgen flag -v) version of dialect
	Version = ""
)

Variables

This section is empty.

Functions

This section is empty.

Types

type ACCELCAL_VEHICLE_POS

type ACCELCAL_VEHICLE_POS int

ACCELCAL_VEHICLE_POS type

const (
	// ACCELCAL_VEHICLE_POS_LEVEL enum
	ACCELCAL_VEHICLE_POS_LEVEL ACCELCAL_VEHICLE_POS = 1
	// ACCELCAL_VEHICLE_POS_LEFT enum
	ACCELCAL_VEHICLE_POS_LEFT ACCELCAL_VEHICLE_POS = 2
	// ACCELCAL_VEHICLE_POS_RIGHT enum
	ACCELCAL_VEHICLE_POS_RIGHT ACCELCAL_VEHICLE_POS = 3
	// ACCELCAL_VEHICLE_POS_NOSEDOWN enum
	ACCELCAL_VEHICLE_POS_NOSEDOWN ACCELCAL_VEHICLE_POS = 4
	// ACCELCAL_VEHICLE_POS_NOSEUP enum
	ACCELCAL_VEHICLE_POS_NOSEUP ACCELCAL_VEHICLE_POS = 5
	// ACCELCAL_VEHICLE_POS_BACK enum
	ACCELCAL_VEHICLE_POS_BACK ACCELCAL_VEHICLE_POS = 6
	// ACCELCAL_VEHICLE_POS_SUCCESS enum
	ACCELCAL_VEHICLE_POS_SUCCESS ACCELCAL_VEHICLE_POS = 16777215
	// ACCELCAL_VEHICLE_POS_FAILED enum
	ACCELCAL_VEHICLE_POS_FAILED ACCELCAL_VEHICLE_POS = 16777216
)

func (ACCELCAL_VEHICLE_POS) Bitmask

func (e ACCELCAL_VEHICLE_POS) Bitmask() string

Bitmask return string representetion of intersects ACCELCAL_VEHICLE_POS enums

func (ACCELCAL_VEHICLE_POS) MarshalBinary

func (e ACCELCAL_VEHICLE_POS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (ACCELCAL_VEHICLE_POS) String

func (e ACCELCAL_VEHICLE_POS) String() string

func (*ACCELCAL_VEHICLE_POS) UnmarshalBinary

func (e *ACCELCAL_VEHICLE_POS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type ADSB_ALTITUDE_TYPE

type ADSB_ALTITUDE_TYPE int

ADSB_ALTITUDE_TYPE type. Enumeration of the ADSB altimeter types

const (
	// ADSB_ALTITUDE_TYPE_PRESSURE_QNH enum. Altitude reported from a Baro source using QNH reference
	ADSB_ALTITUDE_TYPE_PRESSURE_QNH ADSB_ALTITUDE_TYPE = 0
	// ADSB_ALTITUDE_TYPE_GEOMETRIC enum. Altitude reported from a GNSS source
	ADSB_ALTITUDE_TYPE_GEOMETRIC ADSB_ALTITUDE_TYPE = 1
)

func (ADSB_ALTITUDE_TYPE) Bitmask

func (e ADSB_ALTITUDE_TYPE) Bitmask() string

Bitmask return string representetion of intersects ADSB_ALTITUDE_TYPE enums

func (ADSB_ALTITUDE_TYPE) MarshalBinary

func (e ADSB_ALTITUDE_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (ADSB_ALTITUDE_TYPE) String

func (e ADSB_ALTITUDE_TYPE) String() string

func (*ADSB_ALTITUDE_TYPE) UnmarshalBinary

func (e *ADSB_ALTITUDE_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type ADSB_EMITTER_TYPE

type ADSB_EMITTER_TYPE int

ADSB_EMITTER_TYPE type. ADSB classification for the type of vehicle emitting the transponder signal

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

func (ADSB_EMITTER_TYPE) Bitmask

func (e ADSB_EMITTER_TYPE) Bitmask() string

Bitmask return string representetion of intersects ADSB_EMITTER_TYPE enums

func (ADSB_EMITTER_TYPE) MarshalBinary

func (e ADSB_EMITTER_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (ADSB_EMITTER_TYPE) String

func (e ADSB_EMITTER_TYPE) String() string

func (*ADSB_EMITTER_TYPE) UnmarshalBinary

func (e *ADSB_EMITTER_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type ADSB_FLAGS

type ADSB_FLAGS int

ADSB_FLAGS type. These flags indicate status such as data validity of each data source. Set = data valid

const (
	// ADSB_FLAGS_VALID_COORDS enum
	ADSB_FLAGS_VALID_COORDS ADSB_FLAGS = 1
	// ADSB_FLAGS_VALID_ALTITUDE enum
	ADSB_FLAGS_VALID_ALTITUDE ADSB_FLAGS = 2
	// ADSB_FLAGS_VALID_HEADING enum
	ADSB_FLAGS_VALID_HEADING ADSB_FLAGS = 4
	// ADSB_FLAGS_VALID_VELOCITY enum
	ADSB_FLAGS_VALID_VELOCITY ADSB_FLAGS = 8
	// ADSB_FLAGS_VALID_CALLSIGN enum
	ADSB_FLAGS_VALID_CALLSIGN ADSB_FLAGS = 16
	// ADSB_FLAGS_VALID_SQUAWK enum
	ADSB_FLAGS_VALID_SQUAWK ADSB_FLAGS = 32
	// ADSB_FLAGS_SIMULATED enum
	ADSB_FLAGS_SIMULATED ADSB_FLAGS = 64
	// ADSB_FLAGS_VERTICAL_VELOCITY_VALID enum
	ADSB_FLAGS_VERTICAL_VELOCITY_VALID ADSB_FLAGS = 128
	// ADSB_FLAGS_BARO_VALID enum
	ADSB_FLAGS_BARO_VALID ADSB_FLAGS = 256
	// ADSB_FLAGS_SOURCE_UAT enum
	ADSB_FLAGS_SOURCE_UAT ADSB_FLAGS = 32768
)

func (ADSB_FLAGS) Bitmask

func (e ADSB_FLAGS) Bitmask() string

Bitmask return string representetion of intersects ADSB_FLAGS enums

func (ADSB_FLAGS) MarshalBinary

func (e ADSB_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (ADSB_FLAGS) String

func (e ADSB_FLAGS) String() string

func (*ADSB_FLAGS) UnmarshalBinary

func (e *ADSB_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type AIS_FLAGS

type AIS_FLAGS int

AIS_FLAGS type. These flags are used in the AIS_VESSEL.fields bitmask to indicate validity of data in the other message fields. When set, the data is valid.

const (
	// AIS_FLAGS_POSITION_ACCURACY enum. 1 = Position accuracy less than 10m, 0 = position accuracy greater than 10m
	AIS_FLAGS_POSITION_ACCURACY AIS_FLAGS = 1
	// AIS_FLAGS_VALID_COG enum
	AIS_FLAGS_VALID_COG AIS_FLAGS = 2
	// AIS_FLAGS_VALID_VELOCITY enum
	AIS_FLAGS_VALID_VELOCITY AIS_FLAGS = 4
	// AIS_FLAGS_HIGH_VELOCITY enum. 1 = Velocity over 52.5765m/s (102.2 knots)
	AIS_FLAGS_HIGH_VELOCITY AIS_FLAGS = 8
	// AIS_FLAGS_VALID_TURN_RATE enum
	AIS_FLAGS_VALID_TURN_RATE AIS_FLAGS = 16
	// AIS_FLAGS_TURN_RATE_SIGN_ONLY enum. Only the sign of the returned turn rate value is valid, either greater than 5deg/30s or less than -5deg/30s
	AIS_FLAGS_TURN_RATE_SIGN_ONLY AIS_FLAGS = 32
	// AIS_FLAGS_VALID_DIMENSIONS enum
	AIS_FLAGS_VALID_DIMENSIONS AIS_FLAGS = 64
	// AIS_FLAGS_LARGE_BOW_DIMENSION enum. Distance to bow is larger than 511m
	AIS_FLAGS_LARGE_BOW_DIMENSION AIS_FLAGS = 128
	// AIS_FLAGS_LARGE_STERN_DIMENSION enum. Distance to stern is larger than 511m
	AIS_FLAGS_LARGE_STERN_DIMENSION AIS_FLAGS = 256
	// AIS_FLAGS_LARGE_PORT_DIMENSION enum. Distance to port side is larger than 63m
	AIS_FLAGS_LARGE_PORT_DIMENSION AIS_FLAGS = 512
	// AIS_FLAGS_LARGE_STARBOARD_DIMENSION enum. Distance to starboard side is larger than 63m
	AIS_FLAGS_LARGE_STARBOARD_DIMENSION AIS_FLAGS = 1024
	// AIS_FLAGS_VALID_CALLSIGN enum
	AIS_FLAGS_VALID_CALLSIGN AIS_FLAGS = 2048
	// AIS_FLAGS_VALID_NAME enum
	AIS_FLAGS_VALID_NAME AIS_FLAGS = 4096
)

func (AIS_FLAGS) Bitmask

func (e AIS_FLAGS) Bitmask() string

Bitmask return string representetion of intersects AIS_FLAGS enums

func (AIS_FLAGS) MarshalBinary

func (e AIS_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (AIS_FLAGS) String

func (e AIS_FLAGS) String() string

func (*AIS_FLAGS) UnmarshalBinary

func (e *AIS_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type AIS_NAV_STATUS

type AIS_NAV_STATUS int

AIS_NAV_STATUS type. Navigational status of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html

const (
	// UNDER_WAY enum. Under way using engine
	UNDER_WAY AIS_NAV_STATUS = 0
	// AIS_NAV_ANCHORED enum
	AIS_NAV_ANCHORED AIS_NAV_STATUS = 1
	// AIS_NAV_UN_COMMANDED enum
	AIS_NAV_UN_COMMANDED AIS_NAV_STATUS = 2
	// AIS_NAV_RESTRICTED_MANOEUVERABILITY enum
	AIS_NAV_RESTRICTED_MANOEUVERABILITY AIS_NAV_STATUS = 3
	// AIS_NAV_DRAUGHT_CONSTRAINED enum
	AIS_NAV_DRAUGHT_CONSTRAINED AIS_NAV_STATUS = 4
	// AIS_NAV_MOORED enum
	AIS_NAV_MOORED AIS_NAV_STATUS = 5
	// AIS_NAV_AGROUND enum
	AIS_NAV_AGROUND AIS_NAV_STATUS = 6
	// AIS_NAV_FISHING enum
	AIS_NAV_FISHING AIS_NAV_STATUS = 7
	// AIS_NAV_SAILING enum
	AIS_NAV_SAILING AIS_NAV_STATUS = 8
	// AIS_NAV_RESERVED_HSC enum
	AIS_NAV_RESERVED_HSC AIS_NAV_STATUS = 9
	// AIS_NAV_RESERVED_WIG enum
	AIS_NAV_RESERVED_WIG AIS_NAV_STATUS = 10
	// AIS_NAV_RESERVED_1 enum
	AIS_NAV_RESERVED_1 AIS_NAV_STATUS = 11
	// AIS_NAV_RESERVED_2 enum
	AIS_NAV_RESERVED_2 AIS_NAV_STATUS = 12
	// AIS_NAV_RESERVED_3 enum
	AIS_NAV_RESERVED_3 AIS_NAV_STATUS = 13
	// AIS_NAV_AIS_SART enum. Search And Rescue Transponder
	AIS_NAV_AIS_SART AIS_NAV_STATUS = 14
	// AIS_NAV_UNKNOWN enum. Not available (default)
	AIS_NAV_UNKNOWN AIS_NAV_STATUS = 15
)

func (AIS_NAV_STATUS) Bitmask

func (e AIS_NAV_STATUS) Bitmask() string

Bitmask return string representetion of intersects AIS_NAV_STATUS enums

func (AIS_NAV_STATUS) MarshalBinary

func (e AIS_NAV_STATUS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (AIS_NAV_STATUS) String

func (e AIS_NAV_STATUS) String() string

func (*AIS_NAV_STATUS) UnmarshalBinary

func (e *AIS_NAV_STATUS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type AIS_TYPE

type AIS_TYPE int

AIS_TYPE type. Type of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html

const (
	// AIS_TYPE_UNKNOWN enum. Not available (default)
	AIS_TYPE_UNKNOWN AIS_TYPE = 0
	// AIS_TYPE_RESERVED_1 enum
	AIS_TYPE_RESERVED_1 AIS_TYPE = 1
	// AIS_TYPE_RESERVED_2 enum
	AIS_TYPE_RESERVED_2 AIS_TYPE = 2
	// AIS_TYPE_RESERVED_3 enum
	AIS_TYPE_RESERVED_3 AIS_TYPE = 3
	// AIS_TYPE_RESERVED_4 enum
	AIS_TYPE_RESERVED_4 AIS_TYPE = 4
	// AIS_TYPE_RESERVED_5 enum
	AIS_TYPE_RESERVED_5 AIS_TYPE = 5
	// AIS_TYPE_RESERVED_6 enum
	AIS_TYPE_RESERVED_6 AIS_TYPE = 6
	// AIS_TYPE_RESERVED_7 enum
	AIS_TYPE_RESERVED_7 AIS_TYPE = 7
	// AIS_TYPE_RESERVED_8 enum
	AIS_TYPE_RESERVED_8 AIS_TYPE = 8
	// AIS_TYPE_RESERVED_9 enum
	AIS_TYPE_RESERVED_9 AIS_TYPE = 9
	// AIS_TYPE_RESERVED_10 enum
	AIS_TYPE_RESERVED_10 AIS_TYPE = 10
	// AIS_TYPE_RESERVED_11 enum
	AIS_TYPE_RESERVED_11 AIS_TYPE = 11
	// AIS_TYPE_RESERVED_12 enum
	AIS_TYPE_RESERVED_12 AIS_TYPE = 12
	// AIS_TYPE_RESERVED_13 enum
	AIS_TYPE_RESERVED_13 AIS_TYPE = 13
	// AIS_TYPE_RESERVED_14 enum
	AIS_TYPE_RESERVED_14 AIS_TYPE = 14
	// AIS_TYPE_RESERVED_15 enum
	AIS_TYPE_RESERVED_15 AIS_TYPE = 15
	// AIS_TYPE_RESERVED_16 enum
	AIS_TYPE_RESERVED_16 AIS_TYPE = 16
	// AIS_TYPE_RESERVED_17 enum
	AIS_TYPE_RESERVED_17 AIS_TYPE = 17
	// AIS_TYPE_RESERVED_18 enum
	AIS_TYPE_RESERVED_18 AIS_TYPE = 18
	// AIS_TYPE_RESERVED_19 enum
	AIS_TYPE_RESERVED_19 AIS_TYPE = 19
	// AIS_TYPE_WIG enum. Wing In Ground effect
	AIS_TYPE_WIG AIS_TYPE = 20
	// AIS_TYPE_WIG_HAZARDOUS_A enum
	AIS_TYPE_WIG_HAZARDOUS_A AIS_TYPE = 21
	// AIS_TYPE_WIG_HAZARDOUS_B enum
	AIS_TYPE_WIG_HAZARDOUS_B AIS_TYPE = 22
	// AIS_TYPE_WIG_HAZARDOUS_C enum
	AIS_TYPE_WIG_HAZARDOUS_C AIS_TYPE = 23
	// AIS_TYPE_WIG_HAZARDOUS_D enum
	AIS_TYPE_WIG_HAZARDOUS_D AIS_TYPE = 24
	// AIS_TYPE_WIG_RESERVED_1 enum
	AIS_TYPE_WIG_RESERVED_1 AIS_TYPE = 25
	// AIS_TYPE_WIG_RESERVED_2 enum
	AIS_TYPE_WIG_RESERVED_2 AIS_TYPE = 26
	// AIS_TYPE_WIG_RESERVED_3 enum
	AIS_TYPE_WIG_RESERVED_3 AIS_TYPE = 27
	// AIS_TYPE_WIG_RESERVED_4 enum
	AIS_TYPE_WIG_RESERVED_4 AIS_TYPE = 28
	// AIS_TYPE_WIG_RESERVED_5 enum
	AIS_TYPE_WIG_RESERVED_5 AIS_TYPE = 29
	// AIS_TYPE_FISHING enum
	AIS_TYPE_FISHING AIS_TYPE = 30
	// AIS_TYPE_TOWING enum
	AIS_TYPE_TOWING AIS_TYPE = 31
	// AIS_TYPE_TOWING_LARGE enum. Towing: length exceeds 200m or breadth exceeds 25m
	AIS_TYPE_TOWING_LARGE AIS_TYPE = 32
	// AIS_TYPE_DREDGING enum. Dredging or other underwater ops
	AIS_TYPE_DREDGING AIS_TYPE = 33
	// AIS_TYPE_DIVING enum
	AIS_TYPE_DIVING AIS_TYPE = 34
	// AIS_TYPE_MILITARY enum
	AIS_TYPE_MILITARY AIS_TYPE = 35
	// AIS_TYPE_SAILING enum
	AIS_TYPE_SAILING AIS_TYPE = 36
	// AIS_TYPE_PLEASURE enum
	AIS_TYPE_PLEASURE AIS_TYPE = 37
	// AIS_TYPE_RESERVED_20 enum
	AIS_TYPE_RESERVED_20 AIS_TYPE = 38
	// AIS_TYPE_RESERVED_21 enum
	AIS_TYPE_RESERVED_21 AIS_TYPE = 39
	// AIS_TYPE_HSC enum. High Speed Craft
	AIS_TYPE_HSC AIS_TYPE = 40
	// AIS_TYPE_HSC_HAZARDOUS_A enum
	AIS_TYPE_HSC_HAZARDOUS_A AIS_TYPE = 41
	// AIS_TYPE_HSC_HAZARDOUS_B enum
	AIS_TYPE_HSC_HAZARDOUS_B AIS_TYPE = 42
	// AIS_TYPE_HSC_HAZARDOUS_C enum
	AIS_TYPE_HSC_HAZARDOUS_C AIS_TYPE = 43
	// AIS_TYPE_HSC_HAZARDOUS_D enum
	AIS_TYPE_HSC_HAZARDOUS_D AIS_TYPE = 44
	// AIS_TYPE_HSC_RESERVED_1 enum
	AIS_TYPE_HSC_RESERVED_1 AIS_TYPE = 45
	// AIS_TYPE_HSC_RESERVED_2 enum
	AIS_TYPE_HSC_RESERVED_2 AIS_TYPE = 46
	// AIS_TYPE_HSC_RESERVED_3 enum
	AIS_TYPE_HSC_RESERVED_3 AIS_TYPE = 47
	// AIS_TYPE_HSC_RESERVED_4 enum
	AIS_TYPE_HSC_RESERVED_4 AIS_TYPE = 48
	// AIS_TYPE_HSC_UNKNOWN enum
	AIS_TYPE_HSC_UNKNOWN AIS_TYPE = 49
	// AIS_TYPE_PILOT enum
	AIS_TYPE_PILOT AIS_TYPE = 50
	// AIS_TYPE_SAR enum. Search And Rescue vessel
	AIS_TYPE_SAR AIS_TYPE = 51
	// AIS_TYPE_TUG enum
	AIS_TYPE_TUG AIS_TYPE = 52
	// AIS_TYPE_PORT_TENDER enum
	AIS_TYPE_PORT_TENDER AIS_TYPE = 53
	// AIS_TYPE_ANTI_POLLUTION enum. Anti-pollution equipment
	AIS_TYPE_ANTI_POLLUTION AIS_TYPE = 54
	// AIS_TYPE_LAW_ENFORCEMENT enum
	AIS_TYPE_LAW_ENFORCEMENT AIS_TYPE = 55
	// AIS_TYPE_SPARE_LOCAL_1 enum
	AIS_TYPE_SPARE_LOCAL_1 AIS_TYPE = 56
	// AIS_TYPE_SPARE_LOCAL_2 enum
	AIS_TYPE_SPARE_LOCAL_2 AIS_TYPE = 57
	// AIS_TYPE_MEDICAL_TRANSPORT enum
	AIS_TYPE_MEDICAL_TRANSPORT AIS_TYPE = 58
	// AIS_TYPE_NONECOMBATANT enum. Noncombatant ship according to RR Resolution No. 18
	AIS_TYPE_NONECOMBATANT AIS_TYPE = 59
	// AIS_TYPE_PASSENGER enum
	AIS_TYPE_PASSENGER AIS_TYPE = 60
	// AIS_TYPE_PASSENGER_HAZARDOUS_A enum
	AIS_TYPE_PASSENGER_HAZARDOUS_A AIS_TYPE = 61
	// AIS_TYPE_PASSENGER_HAZARDOUS_B enum
	AIS_TYPE_PASSENGER_HAZARDOUS_B AIS_TYPE = 62
	// AIS_TYPE_AIS_TYPE_PASSENGER_HAZARDOUS_C enum
	AIS_TYPE_AIS_TYPE_PASSENGER_HAZARDOUS_C AIS_TYPE = 63
	// AIS_TYPE_PASSENGER_HAZARDOUS_D enum
	AIS_TYPE_PASSENGER_HAZARDOUS_D AIS_TYPE = 64
	// AIS_TYPE_PASSENGER_RESERVED_1 enum
	AIS_TYPE_PASSENGER_RESERVED_1 AIS_TYPE = 65
	// AIS_TYPE_PASSENGER_RESERVED_2 enum
	AIS_TYPE_PASSENGER_RESERVED_2 AIS_TYPE = 66
	// AIS_TYPE_PASSENGER_RESERVED_3 enum
	AIS_TYPE_PASSENGER_RESERVED_3 AIS_TYPE = 67
	// AIS_TYPE_AIS_TYPE_PASSENGER_RESERVED_4 enum
	AIS_TYPE_AIS_TYPE_PASSENGER_RESERVED_4 AIS_TYPE = 68
	// AIS_TYPE_PASSENGER_UNKNOWN enum
	AIS_TYPE_PASSENGER_UNKNOWN AIS_TYPE = 69
	// AIS_TYPE_CARGO enum
	AIS_TYPE_CARGO AIS_TYPE = 70
	// AIS_TYPE_CARGO_HAZARDOUS_A enum
	AIS_TYPE_CARGO_HAZARDOUS_A AIS_TYPE = 71
	// AIS_TYPE_CARGO_HAZARDOUS_B enum
	AIS_TYPE_CARGO_HAZARDOUS_B AIS_TYPE = 72
	// AIS_TYPE_CARGO_HAZARDOUS_C enum
	AIS_TYPE_CARGO_HAZARDOUS_C AIS_TYPE = 73
	// AIS_TYPE_CARGO_HAZARDOUS_D enum
	AIS_TYPE_CARGO_HAZARDOUS_D AIS_TYPE = 74
	// AIS_TYPE_CARGO_RESERVED_1 enum
	AIS_TYPE_CARGO_RESERVED_1 AIS_TYPE = 75
	// AIS_TYPE_CARGO_RESERVED_2 enum
	AIS_TYPE_CARGO_RESERVED_2 AIS_TYPE = 76
	// AIS_TYPE_CARGO_RESERVED_3 enum
	AIS_TYPE_CARGO_RESERVED_3 AIS_TYPE = 77
	// AIS_TYPE_CARGO_RESERVED_4 enum
	AIS_TYPE_CARGO_RESERVED_4 AIS_TYPE = 78
	// AIS_TYPE_CARGO_UNKNOWN enum
	AIS_TYPE_CARGO_UNKNOWN AIS_TYPE = 79
	// AIS_TYPE_TANKER enum
	AIS_TYPE_TANKER AIS_TYPE = 80
	// AIS_TYPE_TANKER_HAZARDOUS_A enum
	AIS_TYPE_TANKER_HAZARDOUS_A AIS_TYPE = 81
	// AIS_TYPE_TANKER_HAZARDOUS_B enum
	AIS_TYPE_TANKER_HAZARDOUS_B AIS_TYPE = 82
	// AIS_TYPE_TANKER_HAZARDOUS_C enum
	AIS_TYPE_TANKER_HAZARDOUS_C AIS_TYPE = 83
	// AIS_TYPE_TANKER_HAZARDOUS_D enum
	AIS_TYPE_TANKER_HAZARDOUS_D AIS_TYPE = 84
	// AIS_TYPE_TANKER_RESERVED_1 enum
	AIS_TYPE_TANKER_RESERVED_1 AIS_TYPE = 85
	// AIS_TYPE_TANKER_RESERVED_2 enum
	AIS_TYPE_TANKER_RESERVED_2 AIS_TYPE = 86
	// AIS_TYPE_TANKER_RESERVED_3 enum
	AIS_TYPE_TANKER_RESERVED_3 AIS_TYPE = 87
	// AIS_TYPE_TANKER_RESERVED_4 enum
	AIS_TYPE_TANKER_RESERVED_4 AIS_TYPE = 88
	// AIS_TYPE_TANKER_UNKNOWN enum
	AIS_TYPE_TANKER_UNKNOWN AIS_TYPE = 89
	// AIS_TYPE_OTHER enum
	AIS_TYPE_OTHER AIS_TYPE = 90
	// AIS_TYPE_OTHER_HAZARDOUS_A enum
	AIS_TYPE_OTHER_HAZARDOUS_A AIS_TYPE = 91
	// AIS_TYPE_OTHER_HAZARDOUS_B enum
	AIS_TYPE_OTHER_HAZARDOUS_B AIS_TYPE = 92
	// AIS_TYPE_OTHER_HAZARDOUS_C enum
	AIS_TYPE_OTHER_HAZARDOUS_C AIS_TYPE = 93
	// AIS_TYPE_OTHER_HAZARDOUS_D enum
	AIS_TYPE_OTHER_HAZARDOUS_D AIS_TYPE = 94
	// AIS_TYPE_OTHER_RESERVED_1 enum
	AIS_TYPE_OTHER_RESERVED_1 AIS_TYPE = 95
	// AIS_TYPE_OTHER_RESERVED_2 enum
	AIS_TYPE_OTHER_RESERVED_2 AIS_TYPE = 96
	// AIS_TYPE_OTHER_RESERVED_3 enum
	AIS_TYPE_OTHER_RESERVED_3 AIS_TYPE = 97
	// AIS_TYPE_OTHER_RESERVED_4 enum
	AIS_TYPE_OTHER_RESERVED_4 AIS_TYPE = 98
	// AIS_TYPE_OTHER_UNKNOWN enum
	AIS_TYPE_OTHER_UNKNOWN AIS_TYPE = 99
)

func (AIS_TYPE) Bitmask

func (e AIS_TYPE) Bitmask() string

Bitmask return string representetion of intersects AIS_TYPE enums

func (AIS_TYPE) MarshalBinary

func (e AIS_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (AIS_TYPE) String

func (e AIS_TYPE) String() string

func (*AIS_TYPE) UnmarshalBinary

func (e *AIS_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type ATTITUDE_TARGET_TYPEMASK

type ATTITUDE_TARGET_TYPEMASK int

ATTITUDE_TARGET_TYPEMASK type. Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates that none of the setpoint dimensions should be ignored.

const (
	// ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE enum. Ignore body roll rate
	ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE ATTITUDE_TARGET_TYPEMASK = 1
	// ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE enum. Ignore body pitch rate
	ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE ATTITUDE_TARGET_TYPEMASK = 2
	// ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE enum. Ignore body yaw rate
	ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE ATTITUDE_TARGET_TYPEMASK = 4
	// ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE enum. Ignore throttle
	ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE ATTITUDE_TARGET_TYPEMASK = 64
	// ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE enum. Ignore attitude
	ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE ATTITUDE_TARGET_TYPEMASK = 128
)

func (ATTITUDE_TARGET_TYPEMASK) Bitmask

func (e ATTITUDE_TARGET_TYPEMASK) Bitmask() string

Bitmask return string representetion of intersects ATTITUDE_TARGET_TYPEMASK enums

func (ATTITUDE_TARGET_TYPEMASK) MarshalBinary

func (e ATTITUDE_TARGET_TYPEMASK) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (ATTITUDE_TARGET_TYPEMASK) String

func (e ATTITUDE_TARGET_TYPEMASK) String() string

func (*ATTITUDE_TARGET_TYPEMASK) UnmarshalBinary

func (e *ATTITUDE_TARGET_TYPEMASK) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type ActuatorControlTarget

type ActuatorControlTarget struct {
	TimeUsec uint64    `json:"TimeUsec" `         // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Controls []float32 `json:"Controls" len:"8" ` // Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.
	GroupMlx uint8     `json:"GroupMlx" `         // Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.
}

ActuatorControlTarget struct (generated typeinfo) Set the vehicle attitude and body angular rates.

func (*ActuatorControlTarget) Dict

func (m *ActuatorControlTarget) Dict() map[string]interface{}

ToMap (generated function)

func (*ActuatorControlTarget) Marshal

func (m *ActuatorControlTarget) Marshal() ([]byte, error)

Marshal (generated function)

func (ActuatorControlTarget) MarshalEasyJSON added in v1.5.0

func (v ActuatorControlTarget) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ActuatorControlTarget) MarshalJSON added in v1.5.0

func (v ActuatorControlTarget) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ActuatorControlTarget) MsgID

MsgID (generated function)

func (*ActuatorControlTarget) String

func (m *ActuatorControlTarget) String() string

String (generated function)

func (*ActuatorControlTarget) Unmarshal

func (m *ActuatorControlTarget) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ActuatorControlTarget) UnmarshalEasyJSON added in v1.5.0

func (v *ActuatorControlTarget) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ActuatorControlTarget) UnmarshalJSON added in v1.5.0

func (v *ActuatorControlTarget) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type AdsbVehicle

type AdsbVehicle struct {
	IcaoAddress  uint32             `json:"IcaoAddress" `      // ICAO address
	Lat          int32              `json:"Lat" `              // [ degE7 ] Latitude
	Lon          int32              `json:"Lon" `              // [ degE7 ] Longitude
	Altitude     int32              `json:"Altitude" `         // [ mm ] Altitude(ASL)
	Heading      uint16             `json:"Heading" `          // [ cdeg ] Course over ground
	HorVelocity  uint16             `json:"HorVelocity" `      // [ cm/s ] The horizontal velocity
	VerVelocity  int16              `json:"VerVelocity" `      // [ cm/s ] The vertical velocity. Positive is up
	Flags        ADSB_FLAGS         `json:"Flags" `            // Bitmap to indicate various statuses including valid data fields
	Squawk       uint16             `json:"Squawk" `           // Squawk code
	AltitudeType ADSB_ALTITUDE_TYPE `json:"AltitudeType" `     // ADSB altitude type.
	Callsign     string             `json:"Callsign" len:"9" ` // The callsign, 8+null
	EmitterType  ADSB_EMITTER_TYPE  `json:"EmitterType" `      // ADSB emitter type.
	Tslc         uint8              `json:"Tslc" `             // [ s ] Time since last communication in seconds
}

AdsbVehicle struct (generated typeinfo) The location and information of an ADSB vehicle

func (*AdsbVehicle) Dict

func (m *AdsbVehicle) Dict() map[string]interface{}

ToMap (generated function)

func (*AdsbVehicle) Marshal

func (m *AdsbVehicle) Marshal() ([]byte, error)

Marshal (generated function)

func (AdsbVehicle) MarshalEasyJSON added in v1.5.0

func (v AdsbVehicle) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (AdsbVehicle) MarshalJSON added in v1.5.0

func (v AdsbVehicle) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*AdsbVehicle) MsgID

func (m *AdsbVehicle) MsgID() message.MessageID

MsgID (generated function)

func (*AdsbVehicle) String

func (m *AdsbVehicle) String() string

String (generated function)

func (*AdsbVehicle) Unmarshal

func (m *AdsbVehicle) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*AdsbVehicle) UnmarshalEasyJSON added in v1.5.0

func (v *AdsbVehicle) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*AdsbVehicle) UnmarshalJSON added in v1.5.0

func (v *AdsbVehicle) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Ahrs

type Ahrs struct {
	Omegaix     float32 `json:"Omegaix" `     // [ rad/s ] X gyro drift estimate.
	Omegaiy     float32 `json:"Omegaiy" `     // [ rad/s ] Y gyro drift estimate.
	Omegaiz     float32 `json:"Omegaiz" `     // [ rad/s ] Z gyro drift estimate.
	AccelWeight float32 `json:"AccelWeight" ` // Average accel_weight.
	RenormVal   float32 `json:"RenormVal" `   // Average renormalisation value.
	ErrorRp     float32 `json:"ErrorRp" `     // Average error_roll_pitch value.
	ErrorYaw    float32 `json:"ErrorYaw" `    // Average error_yaw value.
}

Ahrs struct (generated typeinfo) Status of DCM attitude estimator.

func (*Ahrs) Dict

func (m *Ahrs) Dict() map[string]interface{}

ToMap (generated function)

func (*Ahrs) Marshal

func (m *Ahrs) Marshal() ([]byte, error)

Marshal (generated function)

func (Ahrs) MarshalEasyJSON added in v1.5.0

func (v Ahrs) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Ahrs) MarshalJSON added in v1.5.0

func (v Ahrs) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Ahrs) MsgID

func (m *Ahrs) MsgID() message.MessageID

MsgID (generated function)

func (*Ahrs) String

func (m *Ahrs) String() string

String (generated function)

func (*Ahrs) Unmarshal

func (m *Ahrs) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Ahrs) UnmarshalEasyJSON added in v1.5.0

func (v *Ahrs) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Ahrs) UnmarshalJSON added in v1.5.0

func (v *Ahrs) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Ahrs2

type Ahrs2 struct {
	Roll     float32 `json:"Roll" `     // [ rad ] Roll angle.
	Pitch    float32 `json:"Pitch" `    // [ rad ] Pitch angle.
	Yaw      float32 `json:"Yaw" `      // [ rad ] Yaw angle.
	Altitude float32 `json:"Altitude" ` // [ m ] Altitude (MSL).
	Lat      int32   `json:"Lat" `      // [ degE7 ] Latitude.
	Lng      int32   `json:"Lng" `      // [ degE7 ] Longitude.
}

Ahrs2 struct (generated typeinfo) Status of secondary AHRS filter if available.

func (*Ahrs2) Dict

func (m *Ahrs2) Dict() map[string]interface{}

ToMap (generated function)

func (*Ahrs2) Marshal

func (m *Ahrs2) Marshal() ([]byte, error)

Marshal (generated function)

func (Ahrs2) MarshalEasyJSON added in v1.5.0

func (v Ahrs2) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Ahrs2) MarshalJSON added in v1.5.0

func (v Ahrs2) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Ahrs2) MsgID

func (m *Ahrs2) MsgID() message.MessageID

MsgID (generated function)

func (*Ahrs2) String

func (m *Ahrs2) String() string

String (generated function)

func (*Ahrs2) Unmarshal

func (m *Ahrs2) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Ahrs2) UnmarshalEasyJSON added in v1.5.0

func (v *Ahrs2) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Ahrs2) UnmarshalJSON added in v1.5.0

func (v *Ahrs2) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Ahrs3

type Ahrs3 struct {
	Roll     float32 `json:"Roll" `     // [ rad ] Roll angle.
	Pitch    float32 `json:"Pitch" `    // [ rad ] Pitch angle.
	Yaw      float32 `json:"Yaw" `      // [ rad ] Yaw angle.
	Altitude float32 `json:"Altitude" ` // [ m ] Altitude (MSL).
	Lat      int32   `json:"Lat" `      // [ degE7 ] Latitude.
	Lng      int32   `json:"Lng" `      // [ degE7 ] Longitude.
	V1       float32 `json:"V1" `       // Test variable1.
	V2       float32 `json:"V2" `       // Test variable2.
	V3       float32 `json:"V3" `       // Test variable3.
	V4       float32 `json:"V4" `       // Test variable4.
}

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

func (*Ahrs3) Dict

func (m *Ahrs3) Dict() map[string]interface{}

ToMap (generated function)

func (*Ahrs3) Marshal

func (m *Ahrs3) Marshal() ([]byte, error)

Marshal (generated function)

func (Ahrs3) MarshalEasyJSON added in v1.5.0

func (v Ahrs3) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Ahrs3) MarshalJSON added in v1.5.0

func (v Ahrs3) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Ahrs3) MsgID

func (m *Ahrs3) MsgID() message.MessageID

MsgID (generated function)

func (*Ahrs3) String

func (m *Ahrs3) String() string

String (generated function)

func (*Ahrs3) Unmarshal

func (m *Ahrs3) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Ahrs3) UnmarshalEasyJSON added in v1.5.0

func (v *Ahrs3) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Ahrs3) UnmarshalJSON added in v1.5.0

func (v *Ahrs3) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type AirspeedAutocal

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

AirspeedAutocal struct (generated typeinfo) Airspeed auto-calibration.

func (*AirspeedAutocal) Dict

func (m *AirspeedAutocal) Dict() map[string]interface{}

ToMap (generated function)

func (*AirspeedAutocal) Marshal

func (m *AirspeedAutocal) Marshal() ([]byte, error)

Marshal (generated function)

func (AirspeedAutocal) MarshalEasyJSON added in v1.5.0

func (v AirspeedAutocal) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (AirspeedAutocal) MarshalJSON added in v1.5.0

func (v AirspeedAutocal) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*AirspeedAutocal) MsgID

func (m *AirspeedAutocal) MsgID() message.MessageID

MsgID (generated function)

func (*AirspeedAutocal) String

func (m *AirspeedAutocal) String() string

String (generated function)

func (*AirspeedAutocal) Unmarshal

func (m *AirspeedAutocal) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*AirspeedAutocal) UnmarshalEasyJSON added in v1.5.0

func (v *AirspeedAutocal) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*AirspeedAutocal) UnmarshalJSON added in v1.5.0

func (v *AirspeedAutocal) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Altitude

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

Altitude struct (generated typeinfo) The current system altitude.

func (*Altitude) Dict

func (m *Altitude) Dict() map[string]interface{}

ToMap (generated function)

func (*Altitude) Marshal

func (m *Altitude) Marshal() ([]byte, error)

Marshal (generated function)

func (Altitude) MarshalEasyJSON added in v1.5.0

func (v Altitude) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Altitude) MarshalJSON added in v1.5.0

func (v Altitude) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Altitude) MsgID

func (m *Altitude) MsgID() message.MessageID

MsgID (generated function)

func (*Altitude) String

func (m *Altitude) String() string

String (generated function)

func (*Altitude) Unmarshal

func (m *Altitude) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Altitude) UnmarshalEasyJSON added in v1.5.0

func (v *Altitude) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Altitude) UnmarshalJSON added in v1.5.0

func (v *Altitude) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ApAdc

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

ApAdc struct (generated typeinfo) Raw ADC output.

func (*ApAdc) Dict

func (m *ApAdc) Dict() map[string]interface{}

ToMap (generated function)

func (*ApAdc) Marshal

func (m *ApAdc) Marshal() ([]byte, error)

Marshal (generated function)

func (ApAdc) MarshalEasyJSON added in v1.5.0

func (v ApAdc) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ApAdc) MarshalJSON added in v1.5.0

func (v ApAdc) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ApAdc) MsgID

func (m *ApAdc) MsgID() message.MessageID

MsgID (generated function)

func (*ApAdc) String

func (m *ApAdc) String() string

String (generated function)

func (*ApAdc) Unmarshal

func (m *ApAdc) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ApAdc) UnmarshalEasyJSON added in v1.5.0

func (v *ApAdc) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ApAdc) UnmarshalJSON added in v1.5.0

func (v *ApAdc) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type AttPosMocap

type AttPosMocap struct {
	TimeUsec uint64    `json:"TimeUsec" `  // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Q        []float32 `json:"Q" len:"4" ` // Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
	X        float32   `json:"X" `         // [ m ] X position (NED)
	Y        float32   `json:"Y" `         // [ m ] Y position (NED)
	Z        float32   `json:"Z" `         // [ m ] Z position (NED)
}

AttPosMocap struct (generated typeinfo) Motion capture attitude and position

func (*AttPosMocap) Dict

func (m *AttPosMocap) Dict() map[string]interface{}

ToMap (generated function)

func (*AttPosMocap) Marshal

func (m *AttPosMocap) Marshal() ([]byte, error)

Marshal (generated function)

func (AttPosMocap) MarshalEasyJSON added in v1.5.0

func (v AttPosMocap) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (AttPosMocap) MarshalJSON added in v1.5.0

func (v AttPosMocap) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*AttPosMocap) MsgID

func (m *AttPosMocap) MsgID() message.MessageID

MsgID (generated function)

func (*AttPosMocap) String

func (m *AttPosMocap) String() string

String (generated function)

func (*AttPosMocap) Unmarshal

func (m *AttPosMocap) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*AttPosMocap) UnmarshalEasyJSON added in v1.5.0

func (v *AttPosMocap) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*AttPosMocap) UnmarshalJSON added in v1.5.0

func (v *AttPosMocap) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Attitude

type Attitude struct {
	TimeBootMs uint32  `json:"TimeBootMs" ` // [ ms ] Timestamp (time since system boot).
	Roll       float32 `json:"Roll" `       // [ rad ] Roll angle (-pi..+pi)
	Pitch      float32 `json:"Pitch" `      // [ rad ] Pitch angle (-pi..+pi)
	Yaw        float32 `json:"Yaw" `        // [ rad ] Yaw angle (-pi..+pi)
	Rollspeed  float32 `json:"Rollspeed" `  // [ rad/s ] Roll angular speed
	Pitchspeed float32 `json:"Pitchspeed" ` // [ rad/s ] Pitch angular speed
	Yawspeed   float32 `json:"Yawspeed" `   // [ rad/s ] Yaw angular speed
}

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

func (*Attitude) Dict

func (m *Attitude) Dict() map[string]interface{}

ToMap (generated function)

func (*Attitude) Marshal

func (m *Attitude) Marshal() ([]byte, error)

Marshal (generated function)

func (Attitude) MarshalEasyJSON added in v1.5.0

func (v Attitude) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Attitude) MarshalJSON added in v1.5.0

func (v Attitude) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Attitude) MsgID

func (m *Attitude) MsgID() message.MessageID

MsgID (generated function)

func (*Attitude) String

func (m *Attitude) String() string

String (generated function)

func (*Attitude) Unmarshal

func (m *Attitude) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Attitude) UnmarshalEasyJSON added in v1.5.0

func (v *Attitude) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Attitude) UnmarshalJSON added in v1.5.0

func (v *Attitude) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type AttitudeQuaternion

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

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

func (*AttitudeQuaternion) Dict

func (m *AttitudeQuaternion) Dict() map[string]interface{}

ToMap (generated function)

func (*AttitudeQuaternion) Marshal

func (m *AttitudeQuaternion) Marshal() ([]byte, error)

Marshal (generated function)

func (AttitudeQuaternion) MarshalEasyJSON added in v1.5.0

func (v AttitudeQuaternion) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (AttitudeQuaternion) MarshalJSON added in v1.5.0

func (v AttitudeQuaternion) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*AttitudeQuaternion) MsgID

MsgID (generated function)

func (*AttitudeQuaternion) String

func (m *AttitudeQuaternion) String() string

String (generated function)

func (*AttitudeQuaternion) Unmarshal

func (m *AttitudeQuaternion) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*AttitudeQuaternion) UnmarshalEasyJSON added in v1.5.0

func (v *AttitudeQuaternion) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*AttitudeQuaternion) UnmarshalJSON added in v1.5.0

func (v *AttitudeQuaternion) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type AttitudeQuaternionCov

type AttitudeQuaternionCov struct {
	TimeUsec   uint64    `json:"TimeUsec" `           // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Q          []float32 `json:"Q" len:"4" `          // Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
	Rollspeed  float32   `json:"Rollspeed" `          // [ rad/s ] Roll angular speed
	Pitchspeed float32   `json:"Pitchspeed" `         // [ rad/s ] Pitch angular speed
	Yawspeed   float32   `json:"Yawspeed" `           // [ rad/s ] Yaw angular speed
	Covariance []float32 `json:"Covariance" len:"9" ` // Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
}

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

func (*AttitudeQuaternionCov) Dict

func (m *AttitudeQuaternionCov) Dict() map[string]interface{}

ToMap (generated function)

func (*AttitudeQuaternionCov) Marshal

func (m *AttitudeQuaternionCov) Marshal() ([]byte, error)

Marshal (generated function)

func (AttitudeQuaternionCov) MarshalEasyJSON added in v1.5.0

func (v AttitudeQuaternionCov) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (AttitudeQuaternionCov) MarshalJSON added in v1.5.0

func (v AttitudeQuaternionCov) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*AttitudeQuaternionCov) MsgID

MsgID (generated function)

func (*AttitudeQuaternionCov) String

func (m *AttitudeQuaternionCov) String() string

String (generated function)

func (*AttitudeQuaternionCov) Unmarshal

func (m *AttitudeQuaternionCov) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*AttitudeQuaternionCov) UnmarshalEasyJSON added in v1.5.0

func (v *AttitudeQuaternionCov) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*AttitudeQuaternionCov) UnmarshalJSON added in v1.5.0

func (v *AttitudeQuaternionCov) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type AttitudeTarget

type AttitudeTarget struct {
	TimeBootMs    uint32                   `json:"TimeBootMs" `    // [ ms ] Timestamp (time since system boot).
	Q             []float32                `json:"Q" len:"4" `     // Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
	BodyRollRate  float32                  `json:"BodyRollRate" `  // [ rad/s ] Body roll rate
	BodyPitchRate float32                  `json:"BodyPitchRate" ` // [ rad/s ] Body pitch rate
	BodyYawRate   float32                  `json:"BodyYawRate" `   // [ rad/s ] Body yaw rate
	Thrust        float32                  `json:"Thrust" `        // Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
	TypeMask      ATTITUDE_TARGET_TYPEMASK `json:"TypeMask" `      // Bitmap to indicate which dimensions should be ignored by the vehicle.
}

AttitudeTarget struct (generated typeinfo) Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way.

func (*AttitudeTarget) Dict

func (m *AttitudeTarget) Dict() map[string]interface{}

ToMap (generated function)

func (*AttitudeTarget) Marshal

func (m *AttitudeTarget) Marshal() ([]byte, error)

Marshal (generated function)

func (AttitudeTarget) MarshalEasyJSON added in v1.5.0

func (v AttitudeTarget) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (AttitudeTarget) MarshalJSON added in v1.5.0

func (v AttitudeTarget) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*AttitudeTarget) MsgID

func (m *AttitudeTarget) MsgID() message.MessageID

MsgID (generated function)

func (*AttitudeTarget) String

func (m *AttitudeTarget) String() string

String (generated function)

func (*AttitudeTarget) Unmarshal

func (m *AttitudeTarget) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*AttitudeTarget) UnmarshalEasyJSON added in v1.5.0

func (v *AttitudeTarget) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*AttitudeTarget) UnmarshalJSON added in v1.5.0

func (v *AttitudeTarget) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type AuthKey

type AuthKey struct {
	Key string `json:"Key" len:"32" ` // key
}

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

func (*AuthKey) Dict

func (m *AuthKey) Dict() map[string]interface{}

ToMap (generated function)

func (*AuthKey) Marshal

func (m *AuthKey) Marshal() ([]byte, error)

Marshal (generated function)

func (AuthKey) MarshalEasyJSON added in v1.5.0

func (v AuthKey) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (AuthKey) MarshalJSON added in v1.5.0

func (v AuthKey) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*AuthKey) MsgID

func (m *AuthKey) MsgID() message.MessageID

MsgID (generated function)

func (*AuthKey) String

func (m *AuthKey) String() string

String (generated function)

func (*AuthKey) Unmarshal

func (m *AuthKey) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*AuthKey) UnmarshalEasyJSON added in v1.5.0

func (v *AuthKey) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*AuthKey) UnmarshalJSON added in v1.5.0

func (v *AuthKey) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type AutopilotVersion

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

AutopilotVersion struct (generated typeinfo) Version and capability of autopilot software. This should be emitted in response to a request with MAV_CMD_REQUEST_MESSAGE.

func (*AutopilotVersion) Dict

func (m *AutopilotVersion) Dict() map[string]interface{}

ToMap (generated function)

func (*AutopilotVersion) Marshal

func (m *AutopilotVersion) Marshal() ([]byte, error)

Marshal (generated function)

func (AutopilotVersion) MarshalEasyJSON added in v1.5.0

func (v AutopilotVersion) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (AutopilotVersion) MarshalJSON added in v1.5.0

func (v AutopilotVersion) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*AutopilotVersion) MsgID

func (m *AutopilotVersion) MsgID() message.MessageID

MsgID (generated function)

func (*AutopilotVersion) String

func (m *AutopilotVersion) String() string

String (generated function)

func (*AutopilotVersion) Unmarshal

func (m *AutopilotVersion) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*AutopilotVersion) UnmarshalEasyJSON added in v1.5.0

func (v *AutopilotVersion) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*AutopilotVersion) UnmarshalJSON added in v1.5.0

func (v *AutopilotVersion) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type AutopilotVersionRequest

type AutopilotVersionRequest struct {
	TargetSystem    uint8 `json:"TargetSystem" `    // System ID.
	TargetComponent uint8 `json:"TargetComponent" ` // Component ID.
}

AutopilotVersionRequest struct (generated typeinfo) Request the autopilot version from the system/component.

func (*AutopilotVersionRequest) Dict

func (m *AutopilotVersionRequest) Dict() map[string]interface{}

ToMap (generated function)

func (*AutopilotVersionRequest) Marshal

func (m *AutopilotVersionRequest) Marshal() ([]byte, error)

Marshal (generated function)

func (AutopilotVersionRequest) MarshalEasyJSON added in v1.5.0

func (v AutopilotVersionRequest) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (AutopilotVersionRequest) MarshalJSON added in v1.5.0

func (v AutopilotVersionRequest) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*AutopilotVersionRequest) MsgID

MsgID (generated function)

func (*AutopilotVersionRequest) String

func (m *AutopilotVersionRequest) String() string

String (generated function)

func (*AutopilotVersionRequest) Unmarshal

func (m *AutopilotVersionRequest) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*AutopilotVersionRequest) UnmarshalEasyJSON added in v1.5.0

func (v *AutopilotVersionRequest) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*AutopilotVersionRequest) UnmarshalJSON added in v1.5.0

func (v *AutopilotVersionRequest) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Battery2

type Battery2 struct {
	Voltage        uint16 `json:"Voltage" `        // [ mV ] Voltage.
	CurrentBattery int16  `json:"CurrentBattery" ` // [ cA ] Battery current, -1: autopilot does not measure the current.
}

Battery2 struct (generated typeinfo) 2nd Battery status

func (*Battery2) Dict

func (m *Battery2) Dict() map[string]interface{}

ToMap (generated function)

func (*Battery2) Marshal

func (m *Battery2) Marshal() ([]byte, error)

Marshal (generated function)

func (Battery2) MarshalEasyJSON added in v1.5.0

func (v Battery2) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Battery2) MarshalJSON added in v1.5.0

func (v Battery2) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Battery2) MsgID

func (m *Battery2) MsgID() message.MessageID

MsgID (generated function)

func (*Battery2) String

func (m *Battery2) String() string

String (generated function)

func (*Battery2) Unmarshal

func (m *Battery2) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Battery2) UnmarshalEasyJSON added in v1.5.0

func (v *Battery2) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Battery2) UnmarshalJSON added in v1.5.0

func (v *Battery2) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type BatteryStatus

type BatteryStatus struct {
	CurrentConsumed  int32                `json:"CurrentConsumed" `   // [ mAh ] Consumed charge, -1: autopilot does not provide consumption estimate
	EnergyConsumed   int32                `json:"EnergyConsumed" `    // [ hJ ] Consumed energy, -1: autopilot does not provide energy consumption estimate
	Temperature      int16                `json:"Temperature" `       // [ cdegC ] Temperature of the battery. INT16_MAX for unknown temperature.
	Voltages         []uint16             `json:"Voltages" len:"10" ` // [ mV ] Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1).
	CurrentBattery   int16                `json:"CurrentBattery" `    // [ cA ] Battery current, -1: autopilot does not measure the current
	ID               uint8                `json:"ID" `                // Battery ID
	BatteryFunction  MAV_BATTERY_FUNCTION `json:"BatteryFunction" `   // Function of the battery
	Type             MAV_BATTERY_TYPE     `json:"Type" `              // Type (chemistry) of the battery
	BatteryRemaining int8                 `json:"BatteryRemaining" `  // [ % ] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.
}

BatteryStatus struct (generated typeinfo) Battery information. Updates GCS with flight controller battery status. Smart batteries also use this message, but may additionally send SMART_BATTERY_INFO.

func (*BatteryStatus) Dict

func (m *BatteryStatus) Dict() map[string]interface{}

ToMap (generated function)

func (*BatteryStatus) Marshal

func (m *BatteryStatus) Marshal() ([]byte, error)

Marshal (generated function)

func (BatteryStatus) MarshalEasyJSON added in v1.5.0

func (v BatteryStatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (BatteryStatus) MarshalJSON added in v1.5.0

func (v BatteryStatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*BatteryStatus) MsgID

func (m *BatteryStatus) MsgID() message.MessageID

MsgID (generated function)

func (*BatteryStatus) String

func (m *BatteryStatus) String() string

String (generated function)

func (*BatteryStatus) Unmarshal

func (m *BatteryStatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*BatteryStatus) UnmarshalEasyJSON added in v1.5.0

func (v *BatteryStatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*BatteryStatus) UnmarshalJSON added in v1.5.0

func (v *BatteryStatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type CAMERA_CAP_FLAGS

type CAMERA_CAP_FLAGS int

CAMERA_CAP_FLAGS type. Camera capability flags (Bitmap)

const (
	// CAMERA_CAP_FLAGS_CAPTURE_VIDEO enum. Camera is able to record video
	CAMERA_CAP_FLAGS_CAPTURE_VIDEO CAMERA_CAP_FLAGS = 1
	// CAMERA_CAP_FLAGS_CAPTURE_IMAGE enum. Camera is able to capture images
	CAMERA_CAP_FLAGS_CAPTURE_IMAGE CAMERA_CAP_FLAGS = 2
	// CAMERA_CAP_FLAGS_HAS_MODES enum. Camera has separate Video and Image/Photo modes (MAV_CMD_SET_CAMERA_MODE)
	CAMERA_CAP_FLAGS_HAS_MODES CAMERA_CAP_FLAGS = 4
	// CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE enum. Camera can capture images while in video mode
	CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE CAMERA_CAP_FLAGS = 8
	// CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE enum. Camera can capture videos while in Photo/Image mode
	CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE CAMERA_CAP_FLAGS = 16
	// CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE enum. Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE)
	CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE CAMERA_CAP_FLAGS = 32
	// CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM enum. Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM)
	CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM CAMERA_CAP_FLAGS = 64
	// CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS enum. Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS)
	CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS CAMERA_CAP_FLAGS = 128
	// CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM enum. Camera has video streaming capabilities (request VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video streaming info)
	CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM CAMERA_CAP_FLAGS = 256
	// CAMERA_CAP_FLAGS_HAS_TRACKING_POINT enum. Camera supports tracking of a point on the camera view
	CAMERA_CAP_FLAGS_HAS_TRACKING_POINT CAMERA_CAP_FLAGS = 512
	// CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE enum. Camera supports tracking of a selection rectangle on the camera view
	CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE CAMERA_CAP_FLAGS = 1024
	// CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS enum. Camera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS)
	CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS CAMERA_CAP_FLAGS = 2048
)

func (CAMERA_CAP_FLAGS) Bitmask

func (e CAMERA_CAP_FLAGS) Bitmask() string

Bitmask return string representetion of intersects CAMERA_CAP_FLAGS enums

func (CAMERA_CAP_FLAGS) MarshalBinary

func (e CAMERA_CAP_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (CAMERA_CAP_FLAGS) String

func (e CAMERA_CAP_FLAGS) String() string

func (*CAMERA_CAP_FLAGS) UnmarshalBinary

func (e *CAMERA_CAP_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type CAMERA_FEEDBACK_FLAGS

type CAMERA_FEEDBACK_FLAGS int

CAMERA_FEEDBACK_FLAGS type

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

func (CAMERA_FEEDBACK_FLAGS) Bitmask

func (e CAMERA_FEEDBACK_FLAGS) Bitmask() string

Bitmask return string representetion of intersects CAMERA_FEEDBACK_FLAGS enums

func (CAMERA_FEEDBACK_FLAGS) MarshalBinary

func (e CAMERA_FEEDBACK_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (CAMERA_FEEDBACK_FLAGS) String

func (e CAMERA_FEEDBACK_FLAGS) String() string

func (*CAMERA_FEEDBACK_FLAGS) UnmarshalBinary

func (e *CAMERA_FEEDBACK_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type CAMERA_MODE

type CAMERA_MODE int

CAMERA_MODE type. Camera Modes.

const (
	// CAMERA_MODE_IMAGE enum. Camera is in image/photo capture mode
	CAMERA_MODE_IMAGE CAMERA_MODE = 0
	// CAMERA_MODE_VIDEO enum. Camera is in video capture mode
	CAMERA_MODE_VIDEO CAMERA_MODE = 1
	// CAMERA_MODE_IMAGE_SURVEY enum. Camera is in image survey capture mode. It allows for camera controller to do specific settings for surveys
	CAMERA_MODE_IMAGE_SURVEY CAMERA_MODE = 2
)

func (CAMERA_MODE) Bitmask

func (e CAMERA_MODE) Bitmask() string

Bitmask return string representetion of intersects CAMERA_MODE enums

func (CAMERA_MODE) MarshalBinary

func (e CAMERA_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (CAMERA_MODE) String

func (e CAMERA_MODE) String() string

func (*CAMERA_MODE) UnmarshalBinary

func (e *CAMERA_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type CAMERA_STATUS_TYPES

type CAMERA_STATUS_TYPES int

CAMERA_STATUS_TYPES type

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

func (CAMERA_STATUS_TYPES) Bitmask

func (e CAMERA_STATUS_TYPES) Bitmask() string

Bitmask return string representetion of intersects CAMERA_STATUS_TYPES enums

func (CAMERA_STATUS_TYPES) MarshalBinary

func (e CAMERA_STATUS_TYPES) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (CAMERA_STATUS_TYPES) String

func (e CAMERA_STATUS_TYPES) String() string

func (*CAMERA_STATUS_TYPES) UnmarshalBinary

func (e *CAMERA_STATUS_TYPES) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type CAMERA_TRACKING_MODE

type CAMERA_TRACKING_MODE int

CAMERA_TRACKING_MODE type. Camera tracking modes

const (
	// CAMERA_TRACKING_MODE_NONE enum. Not tracking
	CAMERA_TRACKING_MODE_NONE CAMERA_TRACKING_MODE = 0
	// CAMERA_TRACKING_MODE_POINT enum. Target is a point
	CAMERA_TRACKING_MODE_POINT CAMERA_TRACKING_MODE = 1
	// CAMERA_TRACKING_MODE_RECTANGLE enum. Target is a rectangle
	CAMERA_TRACKING_MODE_RECTANGLE CAMERA_TRACKING_MODE = 2
)

func (CAMERA_TRACKING_MODE) Bitmask

func (e CAMERA_TRACKING_MODE) Bitmask() string

Bitmask return string representetion of intersects CAMERA_TRACKING_MODE enums

func (CAMERA_TRACKING_MODE) MarshalBinary

func (e CAMERA_TRACKING_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (CAMERA_TRACKING_MODE) String

func (e CAMERA_TRACKING_MODE) String() string

func (*CAMERA_TRACKING_MODE) UnmarshalBinary

func (e *CAMERA_TRACKING_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type CAMERA_TRACKING_STATUS_FLAGS

type CAMERA_TRACKING_STATUS_FLAGS int

CAMERA_TRACKING_STATUS_FLAGS type. Camera tracking status flags

const (
	// CAMERA_TRACKING_STATUS_FLAGS_IDLE enum. Camera is not tracking
	CAMERA_TRACKING_STATUS_FLAGS_IDLE CAMERA_TRACKING_STATUS_FLAGS = 0
	// CAMERA_TRACKING_STATUS_FLAGS_ACTIVE enum. Camera is tracking
	CAMERA_TRACKING_STATUS_FLAGS_ACTIVE CAMERA_TRACKING_STATUS_FLAGS = 1
	// CAMERA_TRACKING_STATUS_FLAGS_ERROR enum. Camera tracking in error state
	CAMERA_TRACKING_STATUS_FLAGS_ERROR CAMERA_TRACKING_STATUS_FLAGS = 2
)

func (CAMERA_TRACKING_STATUS_FLAGS) Bitmask

Bitmask return string representetion of intersects CAMERA_TRACKING_STATUS_FLAGS enums

func (CAMERA_TRACKING_STATUS_FLAGS) MarshalBinary

func (e CAMERA_TRACKING_STATUS_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (CAMERA_TRACKING_STATUS_FLAGS) String

func (*CAMERA_TRACKING_STATUS_FLAGS) UnmarshalBinary

func (e *CAMERA_TRACKING_STATUS_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type CAMERA_TRACKING_TARGET_DATA

type CAMERA_TRACKING_TARGET_DATA int

CAMERA_TRACKING_TARGET_DATA type. Camera tracking target data (shows where tracked target is within image)

const (
	// CAMERA_TRACKING_TARGET_DATA_NONE enum. No target data
	CAMERA_TRACKING_TARGET_DATA_NONE CAMERA_TRACKING_TARGET_DATA = 0
	// CAMERA_TRACKING_TARGET_DATA_EMBEDDED enum. Target data embedded in image data (proprietary)
	CAMERA_TRACKING_TARGET_DATA_EMBEDDED CAMERA_TRACKING_TARGET_DATA = 1
	// CAMERA_TRACKING_TARGET_DATA_RENDERED enum. Target data rendered in image
	CAMERA_TRACKING_TARGET_DATA_RENDERED CAMERA_TRACKING_TARGET_DATA = 2
	// CAMERA_TRACKING_TARGET_DATA_IN_STATUS enum. Target data within status message (Point or Rectangle)
	CAMERA_TRACKING_TARGET_DATA_IN_STATUS CAMERA_TRACKING_TARGET_DATA = 4
)

func (CAMERA_TRACKING_TARGET_DATA) Bitmask

func (e CAMERA_TRACKING_TARGET_DATA) Bitmask() string

Bitmask return string representetion of intersects CAMERA_TRACKING_TARGET_DATA enums

func (CAMERA_TRACKING_TARGET_DATA) MarshalBinary

func (e CAMERA_TRACKING_TARGET_DATA) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (CAMERA_TRACKING_TARGET_DATA) String

func (*CAMERA_TRACKING_TARGET_DATA) UnmarshalBinary

func (e *CAMERA_TRACKING_TARGET_DATA) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type CAMERA_ZOOM_TYPE

type CAMERA_ZOOM_TYPE int

CAMERA_ZOOM_TYPE type. Zoom types for MAV_CMD_SET_CAMERA_ZOOM

const (
	// ZOOM_TYPE_STEP enum. Zoom one step increment (-1 for wide, 1 for tele)
	ZOOM_TYPE_STEP CAMERA_ZOOM_TYPE = 0
	// ZOOM_TYPE_CONTINUOUS enum. Continuous zoom up/down until stopped (-1 for wide, 1 for tele, 0 to stop zooming)
	ZOOM_TYPE_CONTINUOUS CAMERA_ZOOM_TYPE = 1
	// ZOOM_TYPE_RANGE enum. Zoom value as proportion of full camera range (a value between 0.0 and 100.0)
	ZOOM_TYPE_RANGE CAMERA_ZOOM_TYPE = 2
	// ZOOM_TYPE_FOCAL_LENGTH enum. Zoom value/variable focal length in milimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)
	ZOOM_TYPE_FOCAL_LENGTH CAMERA_ZOOM_TYPE = 3
)

func (CAMERA_ZOOM_TYPE) Bitmask

func (e CAMERA_ZOOM_TYPE) Bitmask() string

Bitmask return string representetion of intersects CAMERA_ZOOM_TYPE enums

func (CAMERA_ZOOM_TYPE) MarshalBinary

func (e CAMERA_ZOOM_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (CAMERA_ZOOM_TYPE) String

func (e CAMERA_ZOOM_TYPE) String() string

func (*CAMERA_ZOOM_TYPE) UnmarshalBinary

func (e *CAMERA_ZOOM_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type CELLULAR_CONFIG_RESPONSE

type CELLULAR_CONFIG_RESPONSE int

CELLULAR_CONFIG_RESPONSE type. Possible responses from a CELLULAR_CONFIG message.

const (
	// CELLULAR_CONFIG_RESPONSE_ACCEPTED enum. Changes accepted
	CELLULAR_CONFIG_RESPONSE_ACCEPTED CELLULAR_CONFIG_RESPONSE = 0
	// CELLULAR_CONFIG_RESPONSE_APN_ERROR enum. Invalid APN
	CELLULAR_CONFIG_RESPONSE_APN_ERROR CELLULAR_CONFIG_RESPONSE = 1
	// CELLULAR_CONFIG_RESPONSE_PIN_ERROR enum. Invalid PIN
	CELLULAR_CONFIG_RESPONSE_PIN_ERROR CELLULAR_CONFIG_RESPONSE = 2
	// CELLULAR_CONFIG_RESPONSE_REJECTED enum. Changes rejected
	CELLULAR_CONFIG_RESPONSE_REJECTED CELLULAR_CONFIG_RESPONSE = 3
	// CELLULAR_CONFIG_BLOCKED_PUK_REQUIRED enum. PUK is required to unblock SIM card
	CELLULAR_CONFIG_BLOCKED_PUK_REQUIRED CELLULAR_CONFIG_RESPONSE = 4
)

func (CELLULAR_CONFIG_RESPONSE) Bitmask

func (e CELLULAR_CONFIG_RESPONSE) Bitmask() string

Bitmask return string representetion of intersects CELLULAR_CONFIG_RESPONSE enums

func (CELLULAR_CONFIG_RESPONSE) MarshalBinary

func (e CELLULAR_CONFIG_RESPONSE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (CELLULAR_CONFIG_RESPONSE) String

func (e CELLULAR_CONFIG_RESPONSE) String() string

func (*CELLULAR_CONFIG_RESPONSE) UnmarshalBinary

func (e *CELLULAR_CONFIG_RESPONSE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type CELLULAR_NETWORK_FAILED_REASON

type CELLULAR_NETWORK_FAILED_REASON int

CELLULAR_NETWORK_FAILED_REASON type. These flags are used to diagnose the failure state of CELLULAR_STATUS

const (
	// CELLULAR_NETWORK_FAILED_REASON_NONE enum. No error
	CELLULAR_NETWORK_FAILED_REASON_NONE CELLULAR_NETWORK_FAILED_REASON = 0
	// CELLULAR_NETWORK_FAILED_REASON_UNKNOWN enum. Error state is unknown
	CELLULAR_NETWORK_FAILED_REASON_UNKNOWN CELLULAR_NETWORK_FAILED_REASON = 1
	// CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING enum. SIM is required for the modem but missing
	CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING CELLULAR_NETWORK_FAILED_REASON = 2
	// CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR enum. SIM is available, but not usuable for connection
	CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR CELLULAR_NETWORK_FAILED_REASON = 3
)

func (CELLULAR_NETWORK_FAILED_REASON) Bitmask

Bitmask return string representetion of intersects CELLULAR_NETWORK_FAILED_REASON enums

func (CELLULAR_NETWORK_FAILED_REASON) MarshalBinary

func (e CELLULAR_NETWORK_FAILED_REASON) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (CELLULAR_NETWORK_FAILED_REASON) String

func (*CELLULAR_NETWORK_FAILED_REASON) UnmarshalBinary

func (e *CELLULAR_NETWORK_FAILED_REASON) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type CELLULAR_NETWORK_RADIO_TYPE

type CELLULAR_NETWORK_RADIO_TYPE int

CELLULAR_NETWORK_RADIO_TYPE type. Cellular network radio type

const (
	// CELLULAR_NETWORK_RADIO_TYPE_NONE enum
	CELLULAR_NETWORK_RADIO_TYPE_NONE CELLULAR_NETWORK_RADIO_TYPE = 0
	// CELLULAR_NETWORK_RADIO_TYPE_GSM enum
	CELLULAR_NETWORK_RADIO_TYPE_GSM CELLULAR_NETWORK_RADIO_TYPE = 1
	// CELLULAR_NETWORK_RADIO_TYPE_CDMA enum
	CELLULAR_NETWORK_RADIO_TYPE_CDMA CELLULAR_NETWORK_RADIO_TYPE = 2
	// CELLULAR_NETWORK_RADIO_TYPE_WCDMA enum
	CELLULAR_NETWORK_RADIO_TYPE_WCDMA CELLULAR_NETWORK_RADIO_TYPE = 3
	// CELLULAR_NETWORK_RADIO_TYPE_LTE enum
	CELLULAR_NETWORK_RADIO_TYPE_LTE CELLULAR_NETWORK_RADIO_TYPE = 4
)

func (CELLULAR_NETWORK_RADIO_TYPE) Bitmask

func (e CELLULAR_NETWORK_RADIO_TYPE) Bitmask() string

Bitmask return string representetion of intersects CELLULAR_NETWORK_RADIO_TYPE enums

func (CELLULAR_NETWORK_RADIO_TYPE) MarshalBinary

func (e CELLULAR_NETWORK_RADIO_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (CELLULAR_NETWORK_RADIO_TYPE) String

func (*CELLULAR_NETWORK_RADIO_TYPE) UnmarshalBinary

func (e *CELLULAR_NETWORK_RADIO_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type CELLULAR_STATUS_FLAG

type CELLULAR_STATUS_FLAG int

CELLULAR_STATUS_FLAG type. These flags encode the cellular network status

const (
	// CELLULAR_STATUS_FLAG_UNKNOWN enum. State unknown or not reportable
	CELLULAR_STATUS_FLAG_UNKNOWN CELLULAR_STATUS_FLAG = 0
	// CELLULAR_STATUS_FLAG_FAILED enum. Modem is unusable
	CELLULAR_STATUS_FLAG_FAILED CELLULAR_STATUS_FLAG = 1
	// CELLULAR_STATUS_FLAG_INITIALIZING enum. Modem is being initialized
	CELLULAR_STATUS_FLAG_INITIALIZING CELLULAR_STATUS_FLAG = 2
	// CELLULAR_STATUS_FLAG_LOCKED enum. Modem is locked
	CELLULAR_STATUS_FLAG_LOCKED CELLULAR_STATUS_FLAG = 3
	// CELLULAR_STATUS_FLAG_DISABLED enum. Modem is not enabled and is powered down
	CELLULAR_STATUS_FLAG_DISABLED CELLULAR_STATUS_FLAG = 4
	// CELLULAR_STATUS_FLAG_DISABLING enum. Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state
	CELLULAR_STATUS_FLAG_DISABLING CELLULAR_STATUS_FLAG = 5
	// CELLULAR_STATUS_FLAG_ENABLING enum. Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state
	CELLULAR_STATUS_FLAG_ENABLING CELLULAR_STATUS_FLAG = 6
	// CELLULAR_STATUS_FLAG_ENABLED enum. Modem is enabled and powered on but not registered with a network provider and not available for data connections
	CELLULAR_STATUS_FLAG_ENABLED CELLULAR_STATUS_FLAG = 7
	// CELLULAR_STATUS_FLAG_SEARCHING enum. Modem is searching for a network provider to register
	CELLULAR_STATUS_FLAG_SEARCHING CELLULAR_STATUS_FLAG = 8
	// CELLULAR_STATUS_FLAG_REGISTERED enum. Modem is registered with a network provider, and data connections and messaging may be available for use
	CELLULAR_STATUS_FLAG_REGISTERED CELLULAR_STATUS_FLAG = 9
	// CELLULAR_STATUS_FLAG_DISCONNECTING enum. Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated
	CELLULAR_STATUS_FLAG_DISCONNECTING CELLULAR_STATUS_FLAG = 10
	// CELLULAR_STATUS_FLAG_CONNECTING enum. Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered
	CELLULAR_STATUS_FLAG_CONNECTING CELLULAR_STATUS_FLAG = 11
	// CELLULAR_STATUS_FLAG_CONNECTED enum. One or more packet data bearers is active and connected
	CELLULAR_STATUS_FLAG_CONNECTED CELLULAR_STATUS_FLAG = 12
)

func (CELLULAR_STATUS_FLAG) Bitmask

func (e CELLULAR_STATUS_FLAG) Bitmask() string

Bitmask return string representetion of intersects CELLULAR_STATUS_FLAG enums

func (CELLULAR_STATUS_FLAG) MarshalBinary

func (e CELLULAR_STATUS_FLAG) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (CELLULAR_STATUS_FLAG) String

func (e CELLULAR_STATUS_FLAG) String() string

func (*CELLULAR_STATUS_FLAG) UnmarshalBinary

func (e *CELLULAR_STATUS_FLAG) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type COMPONENT_CAP_FLAGS

type COMPONENT_CAP_FLAGS int

COMPONENT_CAP_FLAGS type. Component capability flags (Bitmap)

const (
	// COMPONENT_CAP_FLAGS_PARAM enum. Component has parameters, and supports the parameter protocol (PARAM messages)
	COMPONENT_CAP_FLAGS_PARAM COMPONENT_CAP_FLAGS = 1
	// COMPONENT_CAP_FLAGS_PARAM_EXT enum. Component has parameters, and supports the extended parameter protocol (PARAM_EXT messages)
	COMPONENT_CAP_FLAGS_PARAM_EXT COMPONENT_CAP_FLAGS = 2
)

func (COMPONENT_CAP_FLAGS) Bitmask

func (e COMPONENT_CAP_FLAGS) Bitmask() string

Bitmask return string representetion of intersects COMPONENT_CAP_FLAGS enums

func (COMPONENT_CAP_FLAGS) MarshalBinary

func (e COMPONENT_CAP_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (COMPONENT_CAP_FLAGS) String

func (e COMPONENT_CAP_FLAGS) String() string

func (*COMPONENT_CAP_FLAGS) UnmarshalBinary

func (e *COMPONENT_CAP_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type COMP_METADATA_TYPE

type COMP_METADATA_TYPE int

COMP_METADATA_TYPE type. Possible values for COMPONENT_INFORMATION.comp_metadata_type.

const (
	// COMP_METADATA_TYPE_VERSION enum. Version information which also includes information on other optional supported COMP_METADATA_TYPE's. Must be supported. Only downloadable from vehicle
	COMP_METADATA_TYPE_VERSION COMP_METADATA_TYPE = 0
	// COMP_METADATA_TYPE_PARAMETER enum. Parameter meta data
	COMP_METADATA_TYPE_PARAMETER COMP_METADATA_TYPE = 1
	// COMP_METADATA_TYPE_COMMANDS enum. Meta data which specifies the commands the vehicle supports. (WIP)
	COMP_METADATA_TYPE_COMMANDS COMP_METADATA_TYPE = 2
)

func (COMP_METADATA_TYPE) Bitmask

func (e COMP_METADATA_TYPE) Bitmask() string

Bitmask return string representetion of intersects COMP_METADATA_TYPE enums

func (COMP_METADATA_TYPE) MarshalBinary

func (e COMP_METADATA_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (COMP_METADATA_TYPE) String

func (e COMP_METADATA_TYPE) String() string

func (*COMP_METADATA_TYPE) UnmarshalBinary

func (e *COMP_METADATA_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type COPTER_MODE

type COPTER_MODE int

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

const (
	// COPTER_MODE_STABILIZE enum
	COPTER_MODE_STABILIZE COPTER_MODE = 0
	// COPTER_MODE_ACRO enum
	COPTER_MODE_ACRO COPTER_MODE = 1
	// COPTER_MODE_ALT_HOLD enum
	COPTER_MODE_ALT_HOLD COPTER_MODE = 2
	// COPTER_MODE_AUTO enum
	COPTER_MODE_AUTO COPTER_MODE = 3
	// COPTER_MODE_GUIDED enum
	COPTER_MODE_GUIDED COPTER_MODE = 4
	// COPTER_MODE_LOITER enum
	COPTER_MODE_LOITER COPTER_MODE = 5
	// COPTER_MODE_RTL enum
	COPTER_MODE_RTL COPTER_MODE = 6
	// COPTER_MODE_CIRCLE enum
	COPTER_MODE_CIRCLE COPTER_MODE = 7
	// COPTER_MODE_LAND enum
	COPTER_MODE_LAND COPTER_MODE = 9
	// COPTER_MODE_DRIFT enum
	COPTER_MODE_DRIFT COPTER_MODE = 11
	// COPTER_MODE_SPORT enum
	COPTER_MODE_SPORT COPTER_MODE = 13
	// COPTER_MODE_FLIP enum
	COPTER_MODE_FLIP COPTER_MODE = 14
	// COPTER_MODE_AUTOTUNE enum
	COPTER_MODE_AUTOTUNE COPTER_MODE = 15
	// COPTER_MODE_POSHOLD enum
	COPTER_MODE_POSHOLD COPTER_MODE = 16
	// COPTER_MODE_BRAKE enum
	COPTER_MODE_BRAKE COPTER_MODE = 17
	// COPTER_MODE_THROW enum
	COPTER_MODE_THROW COPTER_MODE = 18
	// COPTER_MODE_AVOID_ADSB enum
	COPTER_MODE_AVOID_ADSB COPTER_MODE = 19
	// COPTER_MODE_GUIDED_NOGPS enum
	COPTER_MODE_GUIDED_NOGPS COPTER_MODE = 20
	// COPTER_MODE_SMART_RTL enum
	COPTER_MODE_SMART_RTL COPTER_MODE = 21
	// COPTER_MODE_FLOWHOLD enum
	COPTER_MODE_FLOWHOLD COPTER_MODE = 22
	// COPTER_MODE_FOLLOW enum
	COPTER_MODE_FOLLOW COPTER_MODE = 23
	// COPTER_MODE_ZIGZAG enum
	COPTER_MODE_ZIGZAG COPTER_MODE = 24
	// COPTER_MODE_SYSTEMID enum
	COPTER_MODE_SYSTEMID COPTER_MODE = 25
	// COPTER_MODE_AUTOROTATE enum
	COPTER_MODE_AUTOROTATE COPTER_MODE = 26
)

func (COPTER_MODE) Bitmask

func (e COPTER_MODE) Bitmask() string

Bitmask return string representetion of intersects COPTER_MODE enums

func (COPTER_MODE) MarshalBinary

func (e COPTER_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (COPTER_MODE) String

func (e COPTER_MODE) String() string

func (*COPTER_MODE) UnmarshalBinary

func (e *COPTER_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type CameraFeedback

type CameraFeedback struct {
	TimeUsec     uint64                `json:"TimeUsec" `     // [ us ] Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).
	Lat          int32                 `json:"Lat" `          // [ degE7 ] Latitude.
	Lng          int32                 `json:"Lng" `          // [ degE7 ] Longitude.
	AltMsl       float32               `json:"AltMsl" `       // [ m ] Altitude (MSL).
	AltRel       float32               `json:"AltRel" `       // [ m ] Altitude (Relative to HOME location).
	Roll         float32               `json:"Roll" `         // [ deg ] Camera Roll angle (earth frame, +-180).
	Pitch        float32               `json:"Pitch" `        // [ deg ] Camera Pitch angle (earth frame, +-180).
	Yaw          float32               `json:"Yaw" `          // [ deg ] Camera Yaw (earth frame, 0-360, true).
	FocLen       float32               `json:"FocLen" `       // [ mm ] Focal Length.
	ImgIdx       uint16                `json:"ImgIdx" `       // Image index.
	TargetSystem uint8                 `json:"TargetSystem" ` // System ID.
	CamIdx       uint8                 `json:"CamIdx" `       // Camera ID.
	Flags        CAMERA_FEEDBACK_FLAGS `json:"Flags" `        // Feedback flags.
}

CameraFeedback struct (generated typeinfo) Camera Capture Feedback.

func (*CameraFeedback) Dict

func (m *CameraFeedback) Dict() map[string]interface{}

ToMap (generated function)

func (*CameraFeedback) Marshal

func (m *CameraFeedback) Marshal() ([]byte, error)

Marshal (generated function)

func (CameraFeedback) MarshalEasyJSON added in v1.5.0

func (v CameraFeedback) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (CameraFeedback) MarshalJSON added in v1.5.0

func (v CameraFeedback) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*CameraFeedback) MsgID

func (m *CameraFeedback) MsgID() message.MessageID

MsgID (generated function)

func (*CameraFeedback) String

func (m *CameraFeedback) String() string

String (generated function)

func (*CameraFeedback) Unmarshal

func (m *CameraFeedback) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*CameraFeedback) UnmarshalEasyJSON added in v1.5.0

func (v *CameraFeedback) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*CameraFeedback) UnmarshalJSON added in v1.5.0

func (v *CameraFeedback) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type CameraStatus

type CameraStatus struct {
	TimeUsec     uint64              `json:"TimeUsec" `     // [ us ] Image timestamp (since UNIX epoch, according to camera clock).
	P1           float32             `json:"P1" `           // Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
	P2           float32             `json:"P2" `           // Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
	P3           float32             `json:"P3" `           // Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
	P4           float32             `json:"P4" `           // Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
	ImgIdx       uint16              `json:"ImgIdx" `       // Image index.
	TargetSystem uint8               `json:"TargetSystem" ` // System ID.
	CamIdx       uint8               `json:"CamIdx" `       // Camera ID.
	EventID      CAMERA_STATUS_TYPES `json:"EventID" `      // Event type.
}

CameraStatus struct (generated typeinfo) Camera Event.

func (*CameraStatus) Dict

func (m *CameraStatus) Dict() map[string]interface{}

ToMap (generated function)

func (*CameraStatus) Marshal

func (m *CameraStatus) Marshal() ([]byte, error)

Marshal (generated function)

func (CameraStatus) MarshalEasyJSON added in v1.5.0

func (v CameraStatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (CameraStatus) MarshalJSON added in v1.5.0

func (v CameraStatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*CameraStatus) MsgID

func (m *CameraStatus) MsgID() message.MessageID

MsgID (generated function)

func (*CameraStatus) String

func (m *CameraStatus) String() string

String (generated function)

func (*CameraStatus) Unmarshal

func (m *CameraStatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*CameraStatus) UnmarshalEasyJSON added in v1.5.0

func (v *CameraStatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*CameraStatus) UnmarshalJSON added in v1.5.0

func (v *CameraStatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type CameraTrigger

type CameraTrigger struct {
	TimeUsec uint64 `json:"TimeUsec" ` // [ us ] Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Seq      uint32 `json:"Seq" `      // Image frame sequence
}

CameraTrigger struct (generated typeinfo) Camera-IMU triggering and synchronisation message.

func (*CameraTrigger) Dict

func (m *CameraTrigger) Dict() map[string]interface{}

ToMap (generated function)

func (*CameraTrigger) Marshal

func (m *CameraTrigger) Marshal() ([]byte, error)

Marshal (generated function)

func (CameraTrigger) MarshalEasyJSON added in v1.5.0

func (v CameraTrigger) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (CameraTrigger) MarshalJSON added in v1.5.0

func (v CameraTrigger) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*CameraTrigger) MsgID

func (m *CameraTrigger) MsgID() message.MessageID

MsgID (generated function)

func (*CameraTrigger) String

func (m *CameraTrigger) String() string

String (generated function)

func (*CameraTrigger) Unmarshal

func (m *CameraTrigger) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*CameraTrigger) UnmarshalEasyJSON added in v1.5.0

func (v *CameraTrigger) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*CameraTrigger) UnmarshalJSON added in v1.5.0

func (v *CameraTrigger) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ChangeOperatorControl

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

ChangeOperatorControl struct (generated typeinfo) Request to control this MAV

func (*ChangeOperatorControl) Dict

func (m *ChangeOperatorControl) Dict() map[string]interface{}

ToMap (generated function)

func (*ChangeOperatorControl) Marshal

func (m *ChangeOperatorControl) Marshal() ([]byte, error)

Marshal (generated function)

func (ChangeOperatorControl) MarshalEasyJSON added in v1.5.0

func (v ChangeOperatorControl) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ChangeOperatorControl) MarshalJSON added in v1.5.0

func (v ChangeOperatorControl) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ChangeOperatorControl) MsgID

MsgID (generated function)

func (*ChangeOperatorControl) String

func (m *ChangeOperatorControl) String() string

String (generated function)

func (*ChangeOperatorControl) Unmarshal

func (m *ChangeOperatorControl) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ChangeOperatorControl) UnmarshalEasyJSON added in v1.5.0

func (v *ChangeOperatorControl) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ChangeOperatorControl) UnmarshalJSON added in v1.5.0

func (v *ChangeOperatorControl) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ChangeOperatorControlAck

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

ChangeOperatorControlAck struct (generated typeinfo) Accept / deny control of this MAV

func (*ChangeOperatorControlAck) Dict

func (m *ChangeOperatorControlAck) Dict() map[string]interface{}

ToMap (generated function)

func (*ChangeOperatorControlAck) Marshal

func (m *ChangeOperatorControlAck) Marshal() ([]byte, error)

Marshal (generated function)

func (ChangeOperatorControlAck) MarshalEasyJSON added in v1.5.0

func (v ChangeOperatorControlAck) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ChangeOperatorControlAck) MarshalJSON added in v1.5.0

func (v ChangeOperatorControlAck) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ChangeOperatorControlAck) MsgID

MsgID (generated function)

func (*ChangeOperatorControlAck) String

func (m *ChangeOperatorControlAck) String() string

String (generated function)

func (*ChangeOperatorControlAck) Unmarshal

func (m *ChangeOperatorControlAck) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ChangeOperatorControlAck) UnmarshalEasyJSON added in v1.5.0

func (v *ChangeOperatorControlAck) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ChangeOperatorControlAck) UnmarshalJSON added in v1.5.0

func (v *ChangeOperatorControlAck) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Collision

type Collision struct {
	ID                     uint32                     `json:"ID" `                     // Unique identifier, domain based on src field
	TimeToMinimumDelta     float32                    `json:"TimeToMinimumDelta" `     // [ s ] Estimated time until collision occurs
	AltitudeMinimumDelta   float32                    `json:"AltitudeMinimumDelta" `   // [ m ] Closest vertical distance between vehicle and object
	HorizontalMinimumDelta float32                    `json:"HorizontalMinimumDelta" ` // [ m ] Closest horizontal distance between vehicle and object
	Src                    MAV_COLLISION_SRC          `json:"Src" `                    // Collision data source
	Action                 MAV_COLLISION_ACTION       `json:"Action" `                 // Action that is being taken to avoid this collision
	ThreatLevel            MAV_COLLISION_THREAT_LEVEL `json:"ThreatLevel" `            // How concerned the aircraft is about this collision
}

Collision struct (generated typeinfo) Information about a potential collision

func (*Collision) Dict

func (m *Collision) Dict() map[string]interface{}

ToMap (generated function)

func (*Collision) Marshal

func (m *Collision) Marshal() ([]byte, error)

Marshal (generated function)

func (Collision) MarshalEasyJSON added in v1.5.0

func (v Collision) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Collision) MarshalJSON added in v1.5.0

func (v Collision) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Collision) MsgID

func (m *Collision) MsgID() message.MessageID

MsgID (generated function)

func (*Collision) String

func (m *Collision) String() string

String (generated function)

func (*Collision) Unmarshal

func (m *Collision) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Collision) UnmarshalEasyJSON added in v1.5.0

func (v *Collision) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Collision) UnmarshalJSON added in v1.5.0

func (v *Collision) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type CommandAck

type CommandAck struct {
	Command MAV_CMD    `json:"Command" ` // Command ID (of acknowledged command).
	Result  MAV_RESULT `json:"Result" `  // Result of command.
}

CommandAck struct (generated typeinfo) Report status of a command. Includes feedback whether the command was executed. The command microservice is documented at https://mavlink.io/en/services/command.html

func (*CommandAck) Dict

func (m *CommandAck) Dict() map[string]interface{}

ToMap (generated function)

func (*CommandAck) Marshal

func (m *CommandAck) Marshal() ([]byte, error)

Marshal (generated function)

func (CommandAck) MarshalEasyJSON added in v1.5.0

func (v CommandAck) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (CommandAck) MarshalJSON added in v1.5.0

func (v CommandAck) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*CommandAck) MsgID

func (m *CommandAck) MsgID() message.MessageID

MsgID (generated function)

func (*CommandAck) String

func (m *CommandAck) String() string

String (generated function)

func (*CommandAck) Unmarshal

func (m *CommandAck) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*CommandAck) UnmarshalEasyJSON added in v1.5.0

func (v *CommandAck) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*CommandAck) UnmarshalJSON added in v1.5.0

func (v *CommandAck) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type CommandCancel

type CommandCancel struct {
	Command         MAV_CMD `json:"Command" `         // Command ID (of command to cancel).
	TargetSystem    uint8   `json:"TargetSystem" `    // System executing long running command. Should not be broadcast (0).
	TargetComponent uint8   `json:"TargetComponent" ` // Component executing long running command.
}

CommandCancel struct (generated typeinfo) Cancel a long running command. The target system should respond with a COMMAND_ACK to the original command with result=MAV_RESULT_CANCELLED if the long running process was cancelled. If it has already completed, the cancel action can be ignored. The cancel action can be retried until some sort of acknowledgement to the original command has been received. The command microservice is documented at https://mavlink.io/en/services/command.html

func (*CommandCancel) Dict

func (m *CommandCancel) Dict() map[string]interface{}

ToMap (generated function)

func (*CommandCancel) Marshal

func (m *CommandCancel) Marshal() ([]byte, error)

Marshal (generated function)

func (CommandCancel) MarshalEasyJSON added in v1.5.0

func (v CommandCancel) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (CommandCancel) MarshalJSON added in v1.5.0

func (v CommandCancel) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*CommandCancel) MsgID

func (m *CommandCancel) MsgID() message.MessageID

MsgID (generated function)

func (*CommandCancel) String

func (m *CommandCancel) String() string

String (generated function)

func (*CommandCancel) Unmarshal

func (m *CommandCancel) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*CommandCancel) UnmarshalEasyJSON added in v1.5.0

func (v *CommandCancel) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*CommandCancel) UnmarshalJSON added in v1.5.0

func (v *CommandCancel) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type CommandInt

type CommandInt struct {
	Param1          float32   `json:"Param1" `          // PARAM1, see MAV_CMD enum
	Param2          float32   `json:"Param2" `          // PARAM2, see MAV_CMD enum
	Param3          float32   `json:"Param3" `          // PARAM3, see MAV_CMD enum
	Param4          float32   `json:"Param4" `          // PARAM4, see MAV_CMD enum
	X               int32     `json:"X" `               // PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
	Y               int32     `json:"Y" `               // PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
	Z               float32   `json:"Z" `               // PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).
	Command         MAV_CMD   `json:"Command" `         // The scheduled action for the mission item.
	TargetSystem    uint8     `json:"TargetSystem" `    // System ID
	TargetComponent uint8     `json:"TargetComponent" ` // Component ID
	Frame           MAV_FRAME `json:"Frame" `           // The coordinate system of the COMMAND.
	Current         uint8     `json:"Current" `         // Not used.
	Autocontinue    uint8     `json:"Autocontinue" `    // Not used (set 0).
}

CommandInt struct (generated typeinfo) Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value. The command microservice is documented at https://mavlink.io/en/services/command.html

func (*CommandInt) Dict

func (m *CommandInt) Dict() map[string]interface{}

ToMap (generated function)

func (*CommandInt) Marshal

func (m *CommandInt) Marshal() ([]byte, error)

Marshal (generated function)

func (CommandInt) MarshalEasyJSON added in v1.5.0

func (v CommandInt) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (CommandInt) MarshalJSON added in v1.5.0

func (v CommandInt) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*CommandInt) MsgID

func (m *CommandInt) MsgID() message.MessageID

MsgID (generated function)

func (*CommandInt) String

func (m *CommandInt) String() string

String (generated function)

func (*CommandInt) Unmarshal

func (m *CommandInt) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*CommandInt) UnmarshalEasyJSON added in v1.5.0

func (v *CommandInt) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*CommandInt) UnmarshalJSON added in v1.5.0

func (v *CommandInt) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type CommandLong

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

CommandLong struct (generated typeinfo) Send a command with up to seven parameters to the MAV. The command microservice is documented at https://mavlink.io/en/services/command.html

func (*CommandLong) Dict

func (m *CommandLong) Dict() map[string]interface{}

ToMap (generated function)

func (*CommandLong) Marshal

func (m *CommandLong) Marshal() ([]byte, error)

Marshal (generated function)

func (CommandLong) MarshalEasyJSON added in v1.5.0

func (v CommandLong) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (CommandLong) MarshalJSON added in v1.5.0

func (v CommandLong) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*CommandLong) MsgID

func (m *CommandLong) MsgID() message.MessageID

MsgID (generated function)

func (*CommandLong) String

func (m *CommandLong) String() string

String (generated function)

func (*CommandLong) Unmarshal

func (m *CommandLong) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*CommandLong) UnmarshalEasyJSON added in v1.5.0

func (v *CommandLong) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*CommandLong) UnmarshalJSON added in v1.5.0

func (v *CommandLong) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type CompassmotStatus

type CompassmotStatus struct {
	Current       float32 `json:"Current" `       // [ A ] Current.
	Compensationx float32 `json:"Compensationx" ` // Motor Compensation X.
	Compensationy float32 `json:"Compensationy" ` // Motor Compensation Y.
	Compensationz float32 `json:"Compensationz" ` // Motor Compensation Z.
	Throttle      uint16  `json:"Throttle" `      // [ d% ] Throttle.
	Interference  uint16  `json:"Interference" `  // [ % ] Interference.
}

CompassmotStatus struct (generated typeinfo) Status of compassmot calibration.

func (*CompassmotStatus) Dict

func (m *CompassmotStatus) Dict() map[string]interface{}

ToMap (generated function)

func (*CompassmotStatus) Marshal

func (m *CompassmotStatus) Marshal() ([]byte, error)

Marshal (generated function)

func (CompassmotStatus) MarshalEasyJSON added in v1.5.0

func (v CompassmotStatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (CompassmotStatus) MarshalJSON added in v1.5.0

func (v CompassmotStatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*CompassmotStatus) MsgID

func (m *CompassmotStatus) MsgID() message.MessageID

MsgID (generated function)

func (*CompassmotStatus) String

func (m *CompassmotStatus) String() string

String (generated function)

func (*CompassmotStatus) Unmarshal

func (m *CompassmotStatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*CompassmotStatus) UnmarshalEasyJSON added in v1.5.0

func (v *CompassmotStatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*CompassmotStatus) UnmarshalJSON added in v1.5.0

func (v *CompassmotStatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ControlSystemState

type ControlSystemState struct {
	TimeUsec    uint64    `json:"TimeUsec" `            // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	XAcc        float32   `json:"XAcc" `                // [ m/s/s ] X acceleration in body frame
	YAcc        float32   `json:"YAcc" `                // [ m/s/s ] Y acceleration in body frame
	ZAcc        float32   `json:"ZAcc" `                // [ m/s/s ] Z acceleration in body frame
	XVel        float32   `json:"XVel" `                // [ m/s ] X velocity in body frame
	YVel        float32   `json:"YVel" `                // [ m/s ] Y velocity in body frame
	ZVel        float32   `json:"ZVel" `                // [ m/s ] Z velocity in body frame
	XPos        float32   `json:"XPos" `                // [ m ] X position in local frame
	YPos        float32   `json:"YPos" `                // [ m ] Y position in local frame
	ZPos        float32   `json:"ZPos" `                // [ m ] Z position in local frame
	Airspeed    float32   `json:"Airspeed" `            // [ m/s ] Airspeed, set to -1 if unknown
	VelVariance []float32 `json:"VelVariance" len:"3" ` // Variance of body velocity estimate
	PosVariance []float32 `json:"PosVariance" len:"3" ` // Variance in local position
	Q           []float32 `json:"Q" len:"4" `           // The attitude, represented as Quaternion
	RollRate    float32   `json:"RollRate" `            // [ rad/s ] Angular rate in roll axis
	PitchRate   float32   `json:"PitchRate" `           // [ rad/s ] Angular rate in pitch axis
	YawRate     float32   `json:"YawRate" `             // [ rad/s ] Angular rate in yaw axis
}

ControlSystemState struct (generated typeinfo) The smoothed, monotonic system state used to feed the control loops of the system.

func (*ControlSystemState) Dict

func (m *ControlSystemState) Dict() map[string]interface{}

ToMap (generated function)

func (*ControlSystemState) Marshal

func (m *ControlSystemState) Marshal() ([]byte, error)

Marshal (generated function)

func (ControlSystemState) MarshalEasyJSON added in v1.5.0

func (v ControlSystemState) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ControlSystemState) MarshalJSON added in v1.5.0

func (v ControlSystemState) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ControlSystemState) MsgID

MsgID (generated function)

func (*ControlSystemState) String

func (m *ControlSystemState) String() string

String (generated function)

func (*ControlSystemState) Unmarshal

func (m *ControlSystemState) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ControlSystemState) UnmarshalEasyJSON added in v1.5.0

func (v *ControlSystemState) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ControlSystemState) UnmarshalJSON added in v1.5.0

func (v *ControlSystemState) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type DEEPSTALL_STAGE

type DEEPSTALL_STAGE int

DEEPSTALL_STAGE type. Deepstall flight stage.

const (
	// DEEPSTALL_STAGE_FLY_TO_LANDING enum. Flying to the landing point
	DEEPSTALL_STAGE_FLY_TO_LANDING DEEPSTALL_STAGE = 0
	// DEEPSTALL_STAGE_ESTIMATE_WIND enum. Building an estimate of the wind
	DEEPSTALL_STAGE_ESTIMATE_WIND DEEPSTALL_STAGE = 1
	// DEEPSTALL_STAGE_WAIT_FOR_BREAKOUT enum. Waiting to breakout of the loiter to fly the approach
	DEEPSTALL_STAGE_WAIT_FOR_BREAKOUT DEEPSTALL_STAGE = 2
	// DEEPSTALL_STAGE_FLY_TO_ARC enum. Flying to the first arc point to turn around to the landing point
	DEEPSTALL_STAGE_FLY_TO_ARC DEEPSTALL_STAGE = 3
	// DEEPSTALL_STAGE_ARC enum. Turning around back to the deepstall landing point
	DEEPSTALL_STAGE_ARC DEEPSTALL_STAGE = 4
	// DEEPSTALL_STAGE_APPROACH enum. Approaching the landing point
	DEEPSTALL_STAGE_APPROACH DEEPSTALL_STAGE = 5
	// DEEPSTALL_STAGE_LAND enum. Stalling and steering towards the land point
	DEEPSTALL_STAGE_LAND DEEPSTALL_STAGE = 6
)

func (DEEPSTALL_STAGE) Bitmask

func (e DEEPSTALL_STAGE) Bitmask() string

Bitmask return string representetion of intersects DEEPSTALL_STAGE enums

func (DEEPSTALL_STAGE) MarshalBinary

func (e DEEPSTALL_STAGE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (DEEPSTALL_STAGE) String

func (e DEEPSTALL_STAGE) String() string

func (*DEEPSTALL_STAGE) UnmarshalBinary

func (e *DEEPSTALL_STAGE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type DEVICE_OP_BUSTYPE

type DEVICE_OP_BUSTYPE int

DEVICE_OP_BUSTYPE type. Bus types for device operations.

const (
	// DEVICE_OP_BUSTYPE_I2C enum. I2C Device operation
	DEVICE_OP_BUSTYPE_I2C DEVICE_OP_BUSTYPE = 0
	// DEVICE_OP_BUSTYPE_SPI enum. SPI Device operation
	DEVICE_OP_BUSTYPE_SPI DEVICE_OP_BUSTYPE = 1
)

func (DEVICE_OP_BUSTYPE) Bitmask

func (e DEVICE_OP_BUSTYPE) Bitmask() string

Bitmask return string representetion of intersects DEVICE_OP_BUSTYPE enums

func (DEVICE_OP_BUSTYPE) MarshalBinary

func (e DEVICE_OP_BUSTYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (DEVICE_OP_BUSTYPE) String

func (e DEVICE_OP_BUSTYPE) String() string

func (*DEVICE_OP_BUSTYPE) UnmarshalBinary

func (e *DEVICE_OP_BUSTYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type Data16

type Data16 struct {
	Type uint8   `json:"Type" `          // Data type.
	Len  uint8   `json:"Len" `           // [ bytes ] Data length.
	Data []uint8 `json:"Data" len:"16" ` // Raw data.
}

Data16 struct (generated typeinfo) Data packet, size 16.

func (*Data16) Dict

func (m *Data16) Dict() map[string]interface{}

ToMap (generated function)

func (*Data16) Marshal

func (m *Data16) Marshal() ([]byte, error)

Marshal (generated function)

func (Data16) MarshalEasyJSON added in v1.5.0

func (v Data16) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Data16) MarshalJSON added in v1.5.0

func (v Data16) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Data16) MsgID

func (m *Data16) MsgID() message.MessageID

MsgID (generated function)

func (*Data16) String

func (m *Data16) String() string

String (generated function)

func (*Data16) Unmarshal

func (m *Data16) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Data16) UnmarshalEasyJSON added in v1.5.0

func (v *Data16) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Data16) UnmarshalJSON added in v1.5.0

func (v *Data16) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Data32

type Data32 struct {
	Type uint8   `json:"Type" `          // Data type.
	Len  uint8   `json:"Len" `           // [ bytes ] Data length.
	Data []uint8 `json:"Data" len:"32" ` // Raw data.
}

Data32 struct (generated typeinfo) Data packet, size 32.

func (*Data32) Dict

func (m *Data32) Dict() map[string]interface{}

ToMap (generated function)

func (*Data32) Marshal

func (m *Data32) Marshal() ([]byte, error)

Marshal (generated function)

func (Data32) MarshalEasyJSON added in v1.5.0

func (v Data32) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Data32) MarshalJSON added in v1.5.0

func (v Data32) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Data32) MsgID

func (m *Data32) MsgID() message.MessageID

MsgID (generated function)

func (*Data32) String

func (m *Data32) String() string

String (generated function)

func (*Data32) Unmarshal

func (m *Data32) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Data32) UnmarshalEasyJSON added in v1.5.0

func (v *Data32) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Data32) UnmarshalJSON added in v1.5.0

func (v *Data32) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Data64

type Data64 struct {
	Type uint8   `json:"Type" `          // Data type.
	Len  uint8   `json:"Len" `           // [ bytes ] Data length.
	Data []uint8 `json:"Data" len:"64" ` // Raw data.
}

Data64 struct (generated typeinfo) Data packet, size 64.

func (*Data64) Dict

func (m *Data64) Dict() map[string]interface{}

ToMap (generated function)

func (*Data64) Marshal

func (m *Data64) Marshal() ([]byte, error)

Marshal (generated function)

func (Data64) MarshalEasyJSON added in v1.5.0

func (v Data64) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Data64) MarshalJSON added in v1.5.0

func (v Data64) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Data64) MsgID

func (m *Data64) MsgID() message.MessageID

MsgID (generated function)

func (*Data64) String

func (m *Data64) String() string

String (generated function)

func (*Data64) Unmarshal

func (m *Data64) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Data64) UnmarshalEasyJSON added in v1.5.0

func (v *Data64) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Data64) UnmarshalJSON added in v1.5.0

func (v *Data64) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Data96

type Data96 struct {
	Type uint8   `json:"Type" `          // Data type.
	Len  uint8   `json:"Len" `           // [ bytes ] Data length.
	Data []uint8 `json:"Data" len:"96" ` // Raw data.
}

Data96 struct (generated typeinfo) Data packet, size 96.

func (*Data96) Dict

func (m *Data96) Dict() map[string]interface{}

ToMap (generated function)

func (*Data96) Marshal

func (m *Data96) Marshal() ([]byte, error)

Marshal (generated function)

func (Data96) MarshalEasyJSON added in v1.5.0

func (v Data96) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Data96) MarshalJSON added in v1.5.0

func (v Data96) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Data96) MsgID

func (m *Data96) MsgID() message.MessageID

MsgID (generated function)

func (*Data96) String

func (m *Data96) String() string

String (generated function)

func (*Data96) Unmarshal

func (m *Data96) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Data96) UnmarshalEasyJSON added in v1.5.0

func (v *Data96) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Data96) UnmarshalJSON added in v1.5.0

func (v *Data96) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type DataStream

type DataStream struct {
	MessageRate uint16 `json:"MessageRate" ` // [ Hz ] The message rate
	StreamID    uint8  `json:"StreamID" `    // The ID of the requested data stream
	OnOff       uint8  `json:"OnOff" `       // 1 stream is enabled, 0 stream is stopped.
}

DataStream struct (generated typeinfo) Data stream status information.

func (*DataStream) Dict

func (m *DataStream) Dict() map[string]interface{}

ToMap (generated function)

func (*DataStream) Marshal

func (m *DataStream) Marshal() ([]byte, error)

Marshal (generated function)

func (DataStream) MarshalEasyJSON added in v1.5.0

func (v DataStream) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (DataStream) MarshalJSON added in v1.5.0

func (v DataStream) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*DataStream) MsgID

func (m *DataStream) MsgID() message.MessageID

MsgID (generated function)

func (*DataStream) String

func (m *DataStream) String() string

String (generated function)

func (*DataStream) Unmarshal

func (m *DataStream) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*DataStream) UnmarshalEasyJSON added in v1.5.0

func (v *DataStream) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*DataStream) UnmarshalJSON added in v1.5.0

func (v *DataStream) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type DataTransmissionHandshake

type DataTransmissionHandshake struct {
	Size       uint32                   `json:"Size" `       // [ bytes ] total data size (set on ACK only).
	Width      uint16                   `json:"Width" `      // Width of a matrix or image.
	Height     uint16                   `json:"Height" `     // Height of a matrix or image.
	Packets    uint16                   `json:"Packets" `    // Number of packets being sent (set on ACK only).
	Type       MAVLINK_DATA_STREAM_TYPE `json:"Type" `       // Type of requested/acknowledged data.
	Payload    uint8                    `json:"Payload" `    // [ bytes ] Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only).
	JpgQuality uint8                    `json:"JpgQuality" ` // [ % ] JPEG quality. Values: [1-100].
}

DataTransmissionHandshake struct (generated typeinfo) Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html.

func (*DataTransmissionHandshake) Dict

func (m *DataTransmissionHandshake) Dict() map[string]interface{}

ToMap (generated function)

func (*DataTransmissionHandshake) Marshal

func (m *DataTransmissionHandshake) Marshal() ([]byte, error)

Marshal (generated function)

func (DataTransmissionHandshake) MarshalEasyJSON added in v1.5.0

func (v DataTransmissionHandshake) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (DataTransmissionHandshake) MarshalJSON added in v1.5.0

func (v DataTransmissionHandshake) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*DataTransmissionHandshake) MsgID

MsgID (generated function)

func (*DataTransmissionHandshake) String

func (m *DataTransmissionHandshake) String() string

String (generated function)

func (*DataTransmissionHandshake) Unmarshal

func (m *DataTransmissionHandshake) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*DataTransmissionHandshake) UnmarshalEasyJSON added in v1.5.0

func (v *DataTransmissionHandshake) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*DataTransmissionHandshake) UnmarshalJSON added in v1.5.0

func (v *DataTransmissionHandshake) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Debug

type Debug struct {
	TimeBootMs uint32  `json:"TimeBootMs" ` // [ ms ] Timestamp (time since system boot).
	Value      float32 `json:"Value" `      // DEBUG value
	Ind        uint8   `json:"Ind" `        // index of debug variable
}

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

func (*Debug) Dict

func (m *Debug) Dict() map[string]interface{}

ToMap (generated function)

func (*Debug) Marshal

func (m *Debug) Marshal() ([]byte, error)

Marshal (generated function)

func (Debug) MarshalEasyJSON added in v1.5.0

func (v Debug) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Debug) MarshalJSON added in v1.5.0

func (v Debug) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Debug) MsgID

func (m *Debug) MsgID() message.MessageID

MsgID (generated function)

func (*Debug) String

func (m *Debug) String() string

String (generated function)

func (*Debug) Unmarshal

func (m *Debug) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Debug) UnmarshalEasyJSON added in v1.5.0

func (v *Debug) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Debug) UnmarshalJSON added in v1.5.0

func (v *Debug) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type DebugVect

type DebugVect struct {
	TimeUsec uint64  `json:"TimeUsec" `      // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	X        float32 `json:"X" `             // x
	Y        float32 `json:"Y" `             // y
	Z        float32 `json:"Z" `             // z
	Name     string  `json:"Name" len:"10" ` // Name
}

DebugVect struct (generated typeinfo) To debug something using a named 3D vector.

func (*DebugVect) Dict

func (m *DebugVect) Dict() map[string]interface{}

ToMap (generated function)

func (*DebugVect) Marshal

func (m *DebugVect) Marshal() ([]byte, error)

Marshal (generated function)

func (DebugVect) MarshalEasyJSON added in v1.5.0

func (v DebugVect) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (DebugVect) MarshalJSON added in v1.5.0

func (v DebugVect) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*DebugVect) MsgID

func (m *DebugVect) MsgID() message.MessageID

MsgID (generated function)

func (*DebugVect) String

func (m *DebugVect) String() string

String (generated function)

func (*DebugVect) Unmarshal

func (m *DebugVect) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*DebugVect) UnmarshalEasyJSON added in v1.5.0

func (v *DebugVect) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*DebugVect) UnmarshalJSON added in v1.5.0

func (v *DebugVect) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Deepstall

type Deepstall struct {
	LandingLat             int32           `json:"LandingLat" `             // [ degE7 ] Landing latitude.
	LandingLon             int32           `json:"LandingLon" `             // [ degE7 ] Landing longitude.
	PathLat                int32           `json:"PathLat" `                // [ degE7 ] Final heading start point, latitude.
	PathLon                int32           `json:"PathLon" `                // [ degE7 ] Final heading start point, longitude.
	ArcEntryLat            int32           `json:"ArcEntryLat" `            // [ degE7 ] Arc entry point, latitude.
	ArcEntryLon            int32           `json:"ArcEntryLon" `            // [ degE7 ] Arc entry point, longitude.
	Altitude               float32         `json:"Altitude" `               // [ m ] Altitude.
	ExpectedTravelDistance float32         `json:"ExpectedTravelDistance" ` // [ m ] Distance the aircraft expects to travel during the deepstall.
	CrossTrackError        float32         `json:"CrossTrackError" `        // [ m ] Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).
	Stage                  DEEPSTALL_STAGE `json:"Stage" `                  // Deepstall stage.
}

Deepstall struct (generated typeinfo) Deepstall path planning.

func (*Deepstall) Dict

func (m *Deepstall) Dict() map[string]interface{}

ToMap (generated function)

func (*Deepstall) Marshal

func (m *Deepstall) Marshal() ([]byte, error)

Marshal (generated function)

func (Deepstall) MarshalEasyJSON added in v1.5.0

func (v Deepstall) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Deepstall) MarshalJSON added in v1.5.0

func (v Deepstall) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Deepstall) MsgID

func (m *Deepstall) MsgID() message.MessageID

MsgID (generated function)

func (*Deepstall) String

func (m *Deepstall) String() string

String (generated function)

func (*Deepstall) Unmarshal

func (m *Deepstall) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Deepstall) UnmarshalEasyJSON added in v1.5.0

func (v *Deepstall) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Deepstall) UnmarshalJSON added in v1.5.0

func (v *Deepstall) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type DigicamConfigure

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

DigicamConfigure struct (generated typeinfo) Configure on-board Camera Control System.

func (*DigicamConfigure) Dict

func (m *DigicamConfigure) Dict() map[string]interface{}

ToMap (generated function)

func (*DigicamConfigure) Marshal

func (m *DigicamConfigure) Marshal() ([]byte, error)

Marshal (generated function)

func (DigicamConfigure) MarshalEasyJSON added in v1.5.0

func (v DigicamConfigure) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (DigicamConfigure) MarshalJSON added in v1.5.0

func (v DigicamConfigure) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*DigicamConfigure) MsgID

func (m *DigicamConfigure) MsgID() message.MessageID

MsgID (generated function)

func (*DigicamConfigure) String

func (m *DigicamConfigure) String() string

String (generated function)

func (*DigicamConfigure) Unmarshal

func (m *DigicamConfigure) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*DigicamConfigure) UnmarshalEasyJSON added in v1.5.0

func (v *DigicamConfigure) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*DigicamConfigure) UnmarshalJSON added in v1.5.0

func (v *DigicamConfigure) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type DigicamControl

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

DigicamControl struct (generated typeinfo) Control on-board Camera Control System to take shots.

func (*DigicamControl) Dict

func (m *DigicamControl) Dict() map[string]interface{}

ToMap (generated function)

func (*DigicamControl) Marshal

func (m *DigicamControl) Marshal() ([]byte, error)

Marshal (generated function)

func (DigicamControl) MarshalEasyJSON added in v1.5.0

func (v DigicamControl) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (DigicamControl) MarshalJSON added in v1.5.0

func (v DigicamControl) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*DigicamControl) MsgID

func (m *DigicamControl) MsgID() message.MessageID

MsgID (generated function)

func (*DigicamControl) String

func (m *DigicamControl) String() string

String (generated function)

func (*DigicamControl) Unmarshal

func (m *DigicamControl) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*DigicamControl) UnmarshalEasyJSON added in v1.5.0

func (v *DigicamControl) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*DigicamControl) UnmarshalJSON added in v1.5.0

func (v *DigicamControl) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type DistanceSensor

type DistanceSensor struct {
	TimeBootMs      uint32                 `json:"TimeBootMs" `      // [ ms ] Timestamp (time since system boot).
	MinDistance     uint16                 `json:"MinDistance" `     // [ cm ] Minimum distance the sensor can measure
	MaxDistance     uint16                 `json:"MaxDistance" `     // [ cm ] Maximum distance the sensor can measure
	CurrentDistance uint16                 `json:"CurrentDistance" ` // [ cm ] Current distance reading
	Type            MAV_DISTANCE_SENSOR    `json:"Type" `            // Type of distance sensor.
	ID              uint8                  `json:"ID" `              // Onboard ID of the sensor
	Orientation     MAV_SENSOR_ORIENTATION `json:"Orientation" `     // Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270
	Covariance      uint8                  `json:"Covariance" `      // [ cm^2 ] Measurement variance. Max standard deviation is 6cm. 255 if unknown.
}

DistanceSensor struct (generated typeinfo) Distance sensor information for an onboard rangefinder.

func (*DistanceSensor) Dict

func (m *DistanceSensor) Dict() map[string]interface{}

ToMap (generated function)

func (*DistanceSensor) Marshal

func (m *DistanceSensor) Marshal() ([]byte, error)

Marshal (generated function)

func (DistanceSensor) MarshalEasyJSON added in v1.5.0

func (v DistanceSensor) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (DistanceSensor) MarshalJSON added in v1.5.0

func (v DistanceSensor) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*DistanceSensor) MsgID

func (m *DistanceSensor) MsgID() message.MessageID

MsgID (generated function)

func (*DistanceSensor) String

func (m *DistanceSensor) String() string

String (generated function)

func (*DistanceSensor) Unmarshal

func (m *DistanceSensor) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*DistanceSensor) UnmarshalEasyJSON added in v1.5.0

func (v *DistanceSensor) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*DistanceSensor) UnmarshalJSON added in v1.5.0

func (v *DistanceSensor) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type EKF_STATUS_FLAGS

type EKF_STATUS_FLAGS int

EKF_STATUS_FLAGS type. Flags in EKF_STATUS message.

const (
	// EKF_ATTITUDE enum. Set if EKF's attitude estimate is good
	EKF_ATTITUDE EKF_STATUS_FLAGS = 1
	// EKF_VELOCITY_HORIZ enum. Set if EKF's horizontal velocity estimate is good
	EKF_VELOCITY_HORIZ EKF_STATUS_FLAGS = 2
	// EKF_VELOCITY_VERT enum. Set if EKF's vertical velocity estimate is good
	EKF_VELOCITY_VERT EKF_STATUS_FLAGS = 4
	// EKF_POS_HORIZ_REL enum. Set if EKF's horizontal position (relative) estimate is good
	EKF_POS_HORIZ_REL EKF_STATUS_FLAGS = 8
	// EKF_POS_HORIZ_ABS enum. Set if EKF's horizontal position (absolute) estimate is good
	EKF_POS_HORIZ_ABS EKF_STATUS_FLAGS = 16
	// EKF_POS_VERT_ABS enum. Set if EKF's vertical position (absolute) estimate is good
	EKF_POS_VERT_ABS EKF_STATUS_FLAGS = 32
	// EKF_POS_VERT_AGL enum. Set if EKF's vertical position (above ground) estimate is good
	EKF_POS_VERT_AGL EKF_STATUS_FLAGS = 64
	// EKF_CONST_POS_MODE enum. EKF is in constant position mode and does not know it's absolute or relative position
	EKF_CONST_POS_MODE EKF_STATUS_FLAGS = 128
	// EKF_PRED_POS_HORIZ_REL enum. Set if EKF's predicted horizontal position (relative) estimate is good
	EKF_PRED_POS_HORIZ_REL EKF_STATUS_FLAGS = 256
	// EKF_PRED_POS_HORIZ_ABS enum. Set if EKF's predicted horizontal position (absolute) estimate is good
	EKF_PRED_POS_HORIZ_ABS EKF_STATUS_FLAGS = 512
	// EKF_UNINITIALIZED enum. Set if EKF has never been healthy
	EKF_UNINITIALIZED EKF_STATUS_FLAGS = 1024
)

func (EKF_STATUS_FLAGS) Bitmask

func (e EKF_STATUS_FLAGS) Bitmask() string

Bitmask return string representetion of intersects EKF_STATUS_FLAGS enums

func (EKF_STATUS_FLAGS) MarshalBinary

func (e EKF_STATUS_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (EKF_STATUS_FLAGS) String

func (e EKF_STATUS_FLAGS) String() string

func (*EKF_STATUS_FLAGS) UnmarshalBinary

func (e *EKF_STATUS_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type ESC_CONNECTION_TYPE

type ESC_CONNECTION_TYPE int

ESC_CONNECTION_TYPE type. Indicates the ESC connection type.

const (
	// ESC_CONNECTION_TYPE_PPM enum. Traditional PPM ESC
	ESC_CONNECTION_TYPE_PPM ESC_CONNECTION_TYPE = 0
	// ESC_CONNECTION_TYPE_SERIAL enum. Serial Bus connected ESC
	ESC_CONNECTION_TYPE_SERIAL ESC_CONNECTION_TYPE = 1
	// ESC_CONNECTION_TYPE_ONESHOT enum. One Shot PPM ESC
	ESC_CONNECTION_TYPE_ONESHOT ESC_CONNECTION_TYPE = 2
	// ESC_CONNECTION_TYPE_I2C enum. I2C ESC
	ESC_CONNECTION_TYPE_I2C ESC_CONNECTION_TYPE = 3
	// ESC_CONNECTION_TYPE_CAN enum. CAN-Bus ESC
	ESC_CONNECTION_TYPE_CAN ESC_CONNECTION_TYPE = 4
	// ESC_CONNECTION_TYPE_DSHOT enum. DShot ESC
	ESC_CONNECTION_TYPE_DSHOT ESC_CONNECTION_TYPE = 5
)

func (ESC_CONNECTION_TYPE) Bitmask

func (e ESC_CONNECTION_TYPE) Bitmask() string

Bitmask return string representetion of intersects ESC_CONNECTION_TYPE enums

func (ESC_CONNECTION_TYPE) MarshalBinary

func (e ESC_CONNECTION_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (ESC_CONNECTION_TYPE) String

func (e ESC_CONNECTION_TYPE) String() string

func (*ESC_CONNECTION_TYPE) UnmarshalBinary

func (e *ESC_CONNECTION_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type ESC_FAILURE_FLAGS

type ESC_FAILURE_FLAGS int

ESC_FAILURE_FLAGS type. Flags to report ESC failures.

const (
	// ESC_FAILURE_NONE enum. No ESC failure
	ESC_FAILURE_NONE ESC_FAILURE_FLAGS = 0
	// ESC_FAILURE_OVER_CURRENT enum. Over current failure
	ESC_FAILURE_OVER_CURRENT ESC_FAILURE_FLAGS = 1
	// ESC_FAILURE_OVER_VOLTAGE enum. Over voltage failure
	ESC_FAILURE_OVER_VOLTAGE ESC_FAILURE_FLAGS = 2
	// ESC_FAILURE_OVER_TEMPERATURE enum. Over temperature failure
	ESC_FAILURE_OVER_TEMPERATURE ESC_FAILURE_FLAGS = 4
	// ESC_FAILURE_OVER_RPM enum. Over RPM failure
	ESC_FAILURE_OVER_RPM ESC_FAILURE_FLAGS = 8
	// ESC_FAILURE_INCONSISTENT_CMD enum. Inconsistent command failure i.e. out of bounds
	ESC_FAILURE_INCONSISTENT_CMD ESC_FAILURE_FLAGS = 16
	// ESC_FAILURE_MOTOR_STUCK enum. Motor stuck failure
	ESC_FAILURE_MOTOR_STUCK ESC_FAILURE_FLAGS = 32
	// ESC_FAILURE_GENERIC enum. Generic ESC failure
	ESC_FAILURE_GENERIC ESC_FAILURE_FLAGS = 64
)

func (ESC_FAILURE_FLAGS) Bitmask

func (e ESC_FAILURE_FLAGS) Bitmask() string

Bitmask return string representetion of intersects ESC_FAILURE_FLAGS enums

func (ESC_FAILURE_FLAGS) MarshalBinary

func (e ESC_FAILURE_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (ESC_FAILURE_FLAGS) String

func (e ESC_FAILURE_FLAGS) String() string

func (*ESC_FAILURE_FLAGS) UnmarshalBinary

func (e *ESC_FAILURE_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type ESTIMATOR_STATUS_FLAGS

type ESTIMATOR_STATUS_FLAGS int

ESTIMATOR_STATUS_FLAGS type. Flags in ESTIMATOR_STATUS message

const (
	// ESTIMATOR_ATTITUDE enum. True if the attitude estimate is good
	ESTIMATOR_ATTITUDE ESTIMATOR_STATUS_FLAGS = 1
	// ESTIMATOR_VELOCITY_HORIZ enum. True if the horizontal velocity estimate is good
	ESTIMATOR_VELOCITY_HORIZ ESTIMATOR_STATUS_FLAGS = 2
	// ESTIMATOR_VELOCITY_VERT enum. True if the  vertical velocity estimate is good
	ESTIMATOR_VELOCITY_VERT ESTIMATOR_STATUS_FLAGS = 4
	// ESTIMATOR_POS_HORIZ_REL enum. True if the horizontal position (relative) estimate is good
	ESTIMATOR_POS_HORIZ_REL ESTIMATOR_STATUS_FLAGS = 8
	// ESTIMATOR_POS_HORIZ_ABS enum. True if the horizontal position (absolute) estimate is good
	ESTIMATOR_POS_HORIZ_ABS ESTIMATOR_STATUS_FLAGS = 16
	// ESTIMATOR_POS_VERT_ABS enum. True if the vertical position (absolute) estimate is good
	ESTIMATOR_POS_VERT_ABS ESTIMATOR_STATUS_FLAGS = 32
	// ESTIMATOR_POS_VERT_AGL enum. True if the vertical position (above ground) estimate is good
	ESTIMATOR_POS_VERT_AGL ESTIMATOR_STATUS_FLAGS = 64
	// ESTIMATOR_CONST_POS_MODE enum. True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)
	ESTIMATOR_CONST_POS_MODE ESTIMATOR_STATUS_FLAGS = 128
	// ESTIMATOR_PRED_POS_HORIZ_REL enum. True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate
	ESTIMATOR_PRED_POS_HORIZ_REL ESTIMATOR_STATUS_FLAGS = 256
	// ESTIMATOR_PRED_POS_HORIZ_ABS enum. True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate
	ESTIMATOR_PRED_POS_HORIZ_ABS ESTIMATOR_STATUS_FLAGS = 512
	// ESTIMATOR_GPS_GLITCH enum. True if the EKF has detected a GPS glitch
	ESTIMATOR_GPS_GLITCH ESTIMATOR_STATUS_FLAGS = 1024
	// ESTIMATOR_ACCEL_ERROR enum. True if the EKF has detected bad accelerometer data
	ESTIMATOR_ACCEL_ERROR ESTIMATOR_STATUS_FLAGS = 2048
)

func (ESTIMATOR_STATUS_FLAGS) Bitmask

func (e ESTIMATOR_STATUS_FLAGS) Bitmask() string

Bitmask return string representetion of intersects ESTIMATOR_STATUS_FLAGS enums

func (ESTIMATOR_STATUS_FLAGS) MarshalBinary

func (e ESTIMATOR_STATUS_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (ESTIMATOR_STATUS_FLAGS) String

func (e ESTIMATOR_STATUS_FLAGS) String() string

func (*ESTIMATOR_STATUS_FLAGS) UnmarshalBinary

func (e *ESTIMATOR_STATUS_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type EfiStatus

type EfiStatus struct {
	EcuIndex                  float32 `json:"EcuIndex" `                  // ECU index
	Rpm                       float32 `json:"Rpm" `                       // RPM
	FuelConsumed              float32 `json:"FuelConsumed" `              // [ cm^3 ] Fuel consumed
	FuelFlow                  float32 `json:"FuelFlow" `                  // [ cm^3/min ] Fuel flow rate
	EngineLoad                float32 `json:"EngineLoad" `                // [ % ] Engine load
	ThrottlePosition          float32 `json:"ThrottlePosition" `          // [ % ] Throttle position
	SparkDwellTime            float32 `json:"SparkDwellTime" `            // [ ms ] Spark dwell time
	BarometricPressure        float32 `json:"BarometricPressure" `        // [ kPa ] Barometric pressure
	IntakeManifoldPressure    float32 `json:"IntakeManifoldPressure" `    // [ kPa ] Intake manifold pressure(
	IntakeManifoldTemperature float32 `json:"IntakeManifoldTemperature" ` // [ degC ] Intake manifold temperature
	CylinderHeadTemperature   float32 `json:"CylinderHeadTemperature" `   // [ degC ] Cylinder head temperature
	IgnitionTiming            float32 `json:"IgnitionTiming" `            // [ deg ] Ignition timing (Crank angle degrees)
	InjectionTime             float32 `json:"InjectionTime" `             // [ ms ] Injection time
	ExhaustGasTemperature     float32 `json:"ExhaustGasTemperature" `     // [ degC ] Exhaust gas temperature
	ThrottleOut               float32 `json:"ThrottleOut" `               // [ % ] Output throttle
	PtCompensation            float32 `json:"PtCompensation" `            // Pressure/temperature compensation
	Health                    uint8   `json:"Health" `                    // EFI health status
}

EfiStatus struct (generated typeinfo) EFI status output

func (*EfiStatus) Dict

func (m *EfiStatus) Dict() map[string]interface{}

ToMap (generated function)

func (*EfiStatus) Marshal

func (m *EfiStatus) Marshal() ([]byte, error)

Marshal (generated function)

func (EfiStatus) MarshalEasyJSON added in v1.5.0

func (v EfiStatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (EfiStatus) MarshalJSON added in v1.5.0

func (v EfiStatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*EfiStatus) MsgID

func (m *EfiStatus) MsgID() message.MessageID

MsgID (generated function)

func (*EfiStatus) String

func (m *EfiStatus) String() string

String (generated function)

func (*EfiStatus) Unmarshal

func (m *EfiStatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*EfiStatus) UnmarshalEasyJSON added in v1.5.0

func (v *EfiStatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*EfiStatus) UnmarshalJSON added in v1.5.0

func (v *EfiStatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type EkfStatusReport

type EkfStatusReport struct {
	VelocityVariance   float32          `json:"VelocityVariance" `   // Velocity variance.
	PosHorizVariance   float32          `json:"PosHorizVariance" `   // Horizontal Position variance.
	PosVertVariance    float32          `json:"PosVertVariance" `    // Vertical Position variance.
	CompassVariance    float32          `json:"CompassVariance" `    // Compass variance.
	TerrainAltVariance float32          `json:"TerrainAltVariance" ` // Terrain Altitude variance.
	Flags              EKF_STATUS_FLAGS `json:"Flags" `              // Flags.
}

EkfStatusReport struct (generated typeinfo) EKF Status message including flags and variances.

func (*EkfStatusReport) Dict

func (m *EkfStatusReport) Dict() map[string]interface{}

ToMap (generated function)

func (*EkfStatusReport) Marshal

func (m *EkfStatusReport) Marshal() ([]byte, error)

Marshal (generated function)

func (EkfStatusReport) MarshalEasyJSON added in v1.5.0

func (v EkfStatusReport) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (EkfStatusReport) MarshalJSON added in v1.5.0

func (v EkfStatusReport) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*EkfStatusReport) MsgID

func (m *EkfStatusReport) MsgID() message.MessageID

MsgID (generated function)

func (*EkfStatusReport) String

func (m *EkfStatusReport) String() string

String (generated function)

func (*EkfStatusReport) Unmarshal

func (m *EkfStatusReport) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*EkfStatusReport) UnmarshalEasyJSON added in v1.5.0

func (v *EkfStatusReport) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*EkfStatusReport) UnmarshalJSON added in v1.5.0

func (v *EkfStatusReport) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type EncapsulatedData

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

EncapsulatedData struct (generated typeinfo) Data packet for images sent using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html.

func (*EncapsulatedData) Dict

func (m *EncapsulatedData) Dict() map[string]interface{}

ToMap (generated function)

func (*EncapsulatedData) Marshal

func (m *EncapsulatedData) Marshal() ([]byte, error)

Marshal (generated function)

func (EncapsulatedData) MarshalEasyJSON added in v1.5.0

func (v EncapsulatedData) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (EncapsulatedData) MarshalJSON added in v1.5.0

func (v EncapsulatedData) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*EncapsulatedData) MsgID

func (m *EncapsulatedData) MsgID() message.MessageID

MsgID (generated function)

func (*EncapsulatedData) String

func (m *EncapsulatedData) String() string

String (generated function)

func (*EncapsulatedData) Unmarshal

func (m *EncapsulatedData) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*EncapsulatedData) UnmarshalEasyJSON added in v1.5.0

func (v *EncapsulatedData) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*EncapsulatedData) UnmarshalJSON added in v1.5.0

func (v *EncapsulatedData) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type EstimatorStatus

type EstimatorStatus struct {
	TimeUsec         uint64                 `json:"TimeUsec" `         // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	VelRatio         float32                `json:"VelRatio" `         // Velocity innovation test ratio
	PosHorizRatio    float32                `json:"PosHorizRatio" `    // Horizontal position innovation test ratio
	PosVertRatio     float32                `json:"PosVertRatio" `     // Vertical position innovation test ratio
	MagRatio         float32                `json:"MagRatio" `         // Magnetometer innovation test ratio
	HaglRatio        float32                `json:"HaglRatio" `        // Height above terrain innovation test ratio
	TasRatio         float32                `json:"TasRatio" `         // True airspeed innovation test ratio
	PosHorizAccuracy float32                `json:"PosHorizAccuracy" ` // [ m ] Horizontal position 1-STD accuracy relative to the EKF local origin
	PosVertAccuracy  float32                `json:"PosVertAccuracy" `  // [ m ] Vertical position 1-STD accuracy relative to the EKF local origin
	Flags            ESTIMATOR_STATUS_FLAGS `json:"Flags" `            // Bitmap indicating which EKF outputs are valid.
}

EstimatorStatus struct (generated typeinfo) Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovation test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovation test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user.

func (*EstimatorStatus) Dict

func (m *EstimatorStatus) Dict() map[string]interface{}

ToMap (generated function)

func (*EstimatorStatus) Marshal

func (m *EstimatorStatus) Marshal() ([]byte, error)

Marshal (generated function)

func (EstimatorStatus) MarshalEasyJSON added in v1.5.0

func (v EstimatorStatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (EstimatorStatus) MarshalJSON added in v1.5.0

func (v EstimatorStatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*EstimatorStatus) MsgID

func (m *EstimatorStatus) MsgID() message.MessageID

MsgID (generated function)

func (*EstimatorStatus) String

func (m *EstimatorStatus) String() string

String (generated function)

func (*EstimatorStatus) Unmarshal

func (m *EstimatorStatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*EstimatorStatus) UnmarshalEasyJSON added in v1.5.0

func (v *EstimatorStatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*EstimatorStatus) UnmarshalJSON added in v1.5.0

func (v *EstimatorStatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ExtendedSysState

type ExtendedSysState struct {
	VtolState   MAV_VTOL_STATE   `json:"VtolState" `   // The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.
	LandedState MAV_LANDED_STATE `json:"LandedState" ` // The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
}

ExtendedSysState struct (generated typeinfo) Provides state for additional features

func (*ExtendedSysState) Dict

func (m *ExtendedSysState) Dict() map[string]interface{}

ToMap (generated function)

func (*ExtendedSysState) Marshal

func (m *ExtendedSysState) Marshal() ([]byte, error)

Marshal (generated function)

func (ExtendedSysState) MarshalEasyJSON added in v1.5.0

func (v ExtendedSysState) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ExtendedSysState) MarshalJSON added in v1.5.0

func (v ExtendedSysState) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ExtendedSysState) MsgID

func (m *ExtendedSysState) MsgID() message.MessageID

MsgID (generated function)

func (*ExtendedSysState) String

func (m *ExtendedSysState) String() string

String (generated function)

func (*ExtendedSysState) Unmarshal

func (m *ExtendedSysState) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ExtendedSysState) UnmarshalEasyJSON added in v1.5.0

func (v *ExtendedSysState) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ExtendedSysState) UnmarshalJSON added in v1.5.0

func (v *ExtendedSysState) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type FAILURE_TYPE

type FAILURE_TYPE int

FAILURE_TYPE type. List of possible failure type to inject.

const (
	// FAILURE_TYPE_OK enum. No failure injected, used to reset a previous failure
	FAILURE_TYPE_OK FAILURE_TYPE = 0
	// FAILURE_TYPE_OFF enum. Sets unit off, so completely non-responsive
	FAILURE_TYPE_OFF FAILURE_TYPE = 1
	// FAILURE_TYPE_STUCK enum. Unit is stuck e.g. keeps reporting the same value
	FAILURE_TYPE_STUCK FAILURE_TYPE = 2
	// FAILURE_TYPE_GARBAGE enum. Unit is reporting complete garbage
	FAILURE_TYPE_GARBAGE FAILURE_TYPE = 3
	// FAILURE_TYPE_WRONG enum. Unit is consistently wrong
	FAILURE_TYPE_WRONG FAILURE_TYPE = 4
	// FAILURE_TYPE_SLOW enum. Unit is slow, so e.g. reporting at slower than expected rate
	FAILURE_TYPE_SLOW FAILURE_TYPE = 5
	// FAILURE_TYPE_DELAYED enum. Data of unit is delayed in time
	FAILURE_TYPE_DELAYED FAILURE_TYPE = 6
	// FAILURE_TYPE_INTERMITTENT enum. Unit is sometimes working, sometimes not
	FAILURE_TYPE_INTERMITTENT FAILURE_TYPE = 7
)

func (FAILURE_TYPE) Bitmask

func (e FAILURE_TYPE) Bitmask() string

Bitmask return string representetion of intersects FAILURE_TYPE enums

func (FAILURE_TYPE) MarshalBinary

func (e FAILURE_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (FAILURE_TYPE) String

func (e FAILURE_TYPE) String() string

func (*FAILURE_TYPE) UnmarshalBinary

func (e *FAILURE_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type FAILURE_UNIT

type FAILURE_UNIT int

FAILURE_UNIT type. List of possible units where failures can be injected.

const (
	// FAILURE_UNIT_SENSOR_GYRO enum
	FAILURE_UNIT_SENSOR_GYRO FAILURE_UNIT = 0
	// FAILURE_UNIT_SENSOR_ACCEL enum
	FAILURE_UNIT_SENSOR_ACCEL FAILURE_UNIT = 1
	// FAILURE_UNIT_SENSOR_MAG enum
	FAILURE_UNIT_SENSOR_MAG FAILURE_UNIT = 2
	// FAILURE_UNIT_SENSOR_BARO enum
	FAILURE_UNIT_SENSOR_BARO FAILURE_UNIT = 3
	// FAILURE_UNIT_SENSOR_GPS enum
	FAILURE_UNIT_SENSOR_GPS FAILURE_UNIT = 4
	// FAILURE_UNIT_SENSOR_OPTICAL_FLOW enum
	FAILURE_UNIT_SENSOR_OPTICAL_FLOW FAILURE_UNIT = 5
	// FAILURE_UNIT_SENSOR_VIO enum
	FAILURE_UNIT_SENSOR_VIO FAILURE_UNIT = 6
	// FAILURE_UNIT_SENSOR_DISTANCE_SENSOR enum
	FAILURE_UNIT_SENSOR_DISTANCE_SENSOR FAILURE_UNIT = 7
	// FAILURE_UNIT_SENSOR_AIRSPEED enum
	FAILURE_UNIT_SENSOR_AIRSPEED FAILURE_UNIT = 8
	// FAILURE_UNIT_SYSTEM_BATTERY enum
	FAILURE_UNIT_SYSTEM_BATTERY FAILURE_UNIT = 100
	// FAILURE_UNIT_SYSTEM_MOTOR enum
	FAILURE_UNIT_SYSTEM_MOTOR FAILURE_UNIT = 101
	// FAILURE_UNIT_SYSTEM_SERVO enum
	FAILURE_UNIT_SYSTEM_SERVO FAILURE_UNIT = 102
	// FAILURE_UNIT_SYSTEM_AVOIDANCE enum
	FAILURE_UNIT_SYSTEM_AVOIDANCE FAILURE_UNIT = 103
	// FAILURE_UNIT_SYSTEM_RC_SIGNAL enum
	FAILURE_UNIT_SYSTEM_RC_SIGNAL FAILURE_UNIT = 104
	// FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL enum
	FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL FAILURE_UNIT = 105
)

func (FAILURE_UNIT) Bitmask

func (e FAILURE_UNIT) Bitmask() string

Bitmask return string representetion of intersects FAILURE_UNIT enums

func (FAILURE_UNIT) MarshalBinary

func (e FAILURE_UNIT) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (FAILURE_UNIT) String

func (e FAILURE_UNIT) String() string

func (*FAILURE_UNIT) UnmarshalBinary

func (e *FAILURE_UNIT) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type FENCE_ACTION

type FENCE_ACTION int

FENCE_ACTION type

const (
	// FENCE_ACTION_NONE enum. Disable fenced mode
	FENCE_ACTION_NONE FENCE_ACTION = 0
	// FENCE_ACTION_GUIDED enum. Switched to guided mode to return point (fence point 0)
	FENCE_ACTION_GUIDED FENCE_ACTION = 1
	// FENCE_ACTION_REPORT enum. Report fence breach, but don't take action
	FENCE_ACTION_REPORT FENCE_ACTION = 2
	// FENCE_ACTION_GUIDED_THR_PASS enum. Switched to guided mode to return point (fence point 0) with manual throttle control
	FENCE_ACTION_GUIDED_THR_PASS FENCE_ACTION = 3
	// FENCE_ACTION_RTL enum. Switch to RTL (return to launch) mode and head for the return point
	FENCE_ACTION_RTL FENCE_ACTION = 4
)

func (FENCE_ACTION) Bitmask

func (e FENCE_ACTION) Bitmask() string

Bitmask return string representetion of intersects FENCE_ACTION enums

func (FENCE_ACTION) MarshalBinary

func (e FENCE_ACTION) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (FENCE_ACTION) String

func (e FENCE_ACTION) String() string

func (*FENCE_ACTION) UnmarshalBinary

func (e *FENCE_ACTION) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type FENCE_BREACH

type FENCE_BREACH int

FENCE_BREACH type

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

func (FENCE_BREACH) Bitmask

func (e FENCE_BREACH) Bitmask() string

Bitmask return string representetion of intersects FENCE_BREACH enums

func (FENCE_BREACH) MarshalBinary

func (e FENCE_BREACH) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (FENCE_BREACH) String

func (e FENCE_BREACH) String() string

func (*FENCE_BREACH) UnmarshalBinary

func (e *FENCE_BREACH) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type FENCE_MITIGATE

type FENCE_MITIGATE int

FENCE_MITIGATE type. Actions being taken to mitigate/prevent fence breach

const (
	// FENCE_MITIGATE_UNKNOWN enum. Unknown
	FENCE_MITIGATE_UNKNOWN FENCE_MITIGATE = 0
	// FENCE_MITIGATE_NONE enum. No actions being taken
	FENCE_MITIGATE_NONE FENCE_MITIGATE = 1
	// FENCE_MITIGATE_VEL_LIMIT enum. Velocity limiting active to prevent breach
	FENCE_MITIGATE_VEL_LIMIT FENCE_MITIGATE = 2
)

func (FENCE_MITIGATE) Bitmask

func (e FENCE_MITIGATE) Bitmask() string

Bitmask return string representetion of intersects FENCE_MITIGATE enums

func (FENCE_MITIGATE) MarshalBinary

func (e FENCE_MITIGATE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (FENCE_MITIGATE) String

func (e FENCE_MITIGATE) String() string

func (*FENCE_MITIGATE) UnmarshalBinary

func (e *FENCE_MITIGATE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type FIRMWARE_VERSION_TYPE

type FIRMWARE_VERSION_TYPE int

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

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

func (FIRMWARE_VERSION_TYPE) Bitmask

func (e FIRMWARE_VERSION_TYPE) Bitmask() string

Bitmask return string representetion of intersects FIRMWARE_VERSION_TYPE enums

func (FIRMWARE_VERSION_TYPE) MarshalBinary

func (e FIRMWARE_VERSION_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (FIRMWARE_VERSION_TYPE) String

func (e FIRMWARE_VERSION_TYPE) String() string

func (*FIRMWARE_VERSION_TYPE) UnmarshalBinary

func (e *FIRMWARE_VERSION_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type FenceFetchPoint

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

FenceFetchPoint struct (generated typeinfo) Request a current fence point from MAV.

func (*FenceFetchPoint) Dict

func (m *FenceFetchPoint) Dict() map[string]interface{}

ToMap (generated function)

func (*FenceFetchPoint) Marshal

func (m *FenceFetchPoint) Marshal() ([]byte, error)

Marshal (generated function)

func (FenceFetchPoint) MarshalEasyJSON added in v1.5.0

func (v FenceFetchPoint) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (FenceFetchPoint) MarshalJSON added in v1.5.0

func (v FenceFetchPoint) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*FenceFetchPoint) MsgID

func (m *FenceFetchPoint) MsgID() message.MessageID

MsgID (generated function)

func (*FenceFetchPoint) String

func (m *FenceFetchPoint) String() string

String (generated function)

func (*FenceFetchPoint) Unmarshal

func (m *FenceFetchPoint) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*FenceFetchPoint) UnmarshalEasyJSON added in v1.5.0

func (v *FenceFetchPoint) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*FenceFetchPoint) UnmarshalJSON added in v1.5.0

func (v *FenceFetchPoint) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type FencePoint

type FencePoint struct {
	Lat             float32 `json:"Lat" `             // [ deg ] Latitude of point.
	Lng             float32 `json:"Lng" `             // [ deg ] Longitude of point.
	TargetSystem    uint8   `json:"TargetSystem" `    // System ID.
	TargetComponent uint8   `json:"TargetComponent" ` // Component ID.
	Idx             uint8   `json:"Idx" `             // Point index (first point is 1, 0 is for return point).
	Count           uint8   `json:"Count" `           // Total number of points (for sanity checking).
}

FencePoint struct (generated typeinfo) A fence point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS.

func (*FencePoint) Dict

func (m *FencePoint) Dict() map[string]interface{}

ToMap (generated function)

func (*FencePoint) Marshal

func (m *FencePoint) Marshal() ([]byte, error)

Marshal (generated function)

func (FencePoint) MarshalEasyJSON added in v1.5.0

func (v FencePoint) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (FencePoint) MarshalJSON added in v1.5.0

func (v FencePoint) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*FencePoint) MsgID

func (m *FencePoint) MsgID() message.MessageID

MsgID (generated function)

func (*FencePoint) String

func (m *FencePoint) String() string

String (generated function)

func (*FencePoint) Unmarshal

func (m *FencePoint) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*FencePoint) UnmarshalEasyJSON added in v1.5.0

func (v *FencePoint) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*FencePoint) UnmarshalJSON added in v1.5.0

func (v *FencePoint) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type FenceStatus

type FenceStatus struct {
	BreachTime   uint32       `json:"BreachTime" `   // [ ms ] Time (since boot) of last breach.
	BreachCount  uint16       `json:"BreachCount" `  // Number of fence breaches.
	BreachStatus uint8        `json:"BreachStatus" ` // Breach status (0 if currently inside fence, 1 if outside).
	BreachType   FENCE_BREACH `json:"BreachType" `   // Last breach type.
}

FenceStatus struct (generated typeinfo) Status of geo-fencing. Sent in extended status stream when fencing enabled.

func (*FenceStatus) Dict

func (m *FenceStatus) Dict() map[string]interface{}

ToMap (generated function)

func (*FenceStatus) Marshal

func (m *FenceStatus) Marshal() ([]byte, error)

Marshal (generated function)

func (FenceStatus) MarshalEasyJSON added in v1.5.0

func (v FenceStatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (FenceStatus) MarshalJSON added in v1.5.0

func (v FenceStatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*FenceStatus) MsgID

func (m *FenceStatus) MsgID() message.MessageID

MsgID (generated function)

func (*FenceStatus) String

func (m *FenceStatus) String() string

String (generated function)

func (*FenceStatus) Unmarshal

func (m *FenceStatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*FenceStatus) UnmarshalEasyJSON added in v1.5.0

func (v *FenceStatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*FenceStatus) UnmarshalJSON added in v1.5.0

func (v *FenceStatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type FileTransferProtocol

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

FileTransferProtocol struct (generated typeinfo) File transfer message

func (*FileTransferProtocol) Dict

func (m *FileTransferProtocol) Dict() map[string]interface{}

ToMap (generated function)

func (*FileTransferProtocol) Marshal

func (m *FileTransferProtocol) Marshal() ([]byte, error)

Marshal (generated function)

func (FileTransferProtocol) MarshalEasyJSON added in v1.5.0

func (v FileTransferProtocol) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (FileTransferProtocol) MarshalJSON added in v1.5.0

func (v FileTransferProtocol) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*FileTransferProtocol) MsgID

MsgID (generated function)

func (*FileTransferProtocol) String

func (m *FileTransferProtocol) String() string

String (generated function)

func (*FileTransferProtocol) Unmarshal

func (m *FileTransferProtocol) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*FileTransferProtocol) UnmarshalEasyJSON added in v1.5.0

func (v *FileTransferProtocol) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*FileTransferProtocol) UnmarshalJSON added in v1.5.0

func (v *FileTransferProtocol) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type FollowTarget

type FollowTarget struct {
	Timestamp       uint64    `json:"Timestamp" `           // [ ms ] Timestamp (time since system boot).
	CustomState     uint64    `json:"CustomState" `         // button states or switches of a tracker device
	Lat             int32     `json:"Lat" `                 // [ degE7 ] Latitude (WGS84)
	Lon             int32     `json:"Lon" `                 // [ degE7 ] Longitude (WGS84)
	Alt             float32   `json:"Alt" `                 // [ m ] Altitude (MSL)
	Vel             []float32 `json:"Vel" len:"3" `         // [ m/s ] target velocity (0,0,0) for unknown
	Acc             []float32 `json:"Acc" len:"3" `         // [ m/s/s ] linear target acceleration (0,0,0) for unknown
	AttitudeQ       []float32 `json:"AttitudeQ" len:"4" `   // (1 0 0 0 for unknown)
	Rates           []float32 `json:"Rates" len:"3" `       // (0 0 0 for unknown)
	PositionCov     []float32 `json:"PositionCov" len:"3" ` // eph epv
	EstCapabilities uint8     `json:"EstCapabilities" `     // bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)
}

FollowTarget struct (generated typeinfo) Current motion information from a designated system

func (*FollowTarget) Dict

func (m *FollowTarget) Dict() map[string]interface{}

ToMap (generated function)

func (*FollowTarget) Marshal

func (m *FollowTarget) Marshal() ([]byte, error)

Marshal (generated function)

func (FollowTarget) MarshalEasyJSON added in v1.5.0

func (v FollowTarget) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (FollowTarget) MarshalJSON added in v1.5.0

func (v FollowTarget) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*FollowTarget) MsgID

func (m *FollowTarget) MsgID() message.MessageID

MsgID (generated function)

func (*FollowTarget) String

func (m *FollowTarget) String() string

String (generated function)

func (*FollowTarget) Unmarshal

func (m *FollowTarget) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*FollowTarget) UnmarshalEasyJSON added in v1.5.0

func (v *FollowTarget) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*FollowTarget) UnmarshalJSON added in v1.5.0

func (v *FollowTarget) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GIMBAL_AXIS

type GIMBAL_AXIS int

GIMBAL_AXIS type

const (
	// GIMBAL_AXIS_YAW enum. Gimbal yaw axis
	GIMBAL_AXIS_YAW GIMBAL_AXIS = 0
	// GIMBAL_AXIS_PITCH enum. Gimbal pitch axis
	GIMBAL_AXIS_PITCH GIMBAL_AXIS = 1
	// GIMBAL_AXIS_ROLL enum. Gimbal roll axis
	GIMBAL_AXIS_ROLL GIMBAL_AXIS = 2
)

func (GIMBAL_AXIS) Bitmask

func (e GIMBAL_AXIS) Bitmask() string

Bitmask return string representetion of intersects GIMBAL_AXIS enums

func (GIMBAL_AXIS) MarshalBinary

func (e GIMBAL_AXIS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GIMBAL_AXIS) String

func (e GIMBAL_AXIS) String() string

func (*GIMBAL_AXIS) UnmarshalBinary

func (e *GIMBAL_AXIS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GIMBAL_AXIS_CALIBRATION_REQUIRED

type GIMBAL_AXIS_CALIBRATION_REQUIRED int

GIMBAL_AXIS_CALIBRATION_REQUIRED type

const (
	// GIMBAL_AXIS_CALIBRATION_REQUIRED_UNKNOWN enum. Whether or not this axis requires calibration is unknown at this time
	GIMBAL_AXIS_CALIBRATION_REQUIRED_UNKNOWN GIMBAL_AXIS_CALIBRATION_REQUIRED = 0
	// GIMBAL_AXIS_CALIBRATION_REQUIRED_TRUE enum. This axis requires calibration
	GIMBAL_AXIS_CALIBRATION_REQUIRED_TRUE GIMBAL_AXIS_CALIBRATION_REQUIRED = 1
	// GIMBAL_AXIS_CALIBRATION_REQUIRED_FALSE enum. This axis does not require calibration
	GIMBAL_AXIS_CALIBRATION_REQUIRED_FALSE GIMBAL_AXIS_CALIBRATION_REQUIRED = 2
)

func (GIMBAL_AXIS_CALIBRATION_REQUIRED) Bitmask

Bitmask return string representetion of intersects GIMBAL_AXIS_CALIBRATION_REQUIRED enums

func (GIMBAL_AXIS_CALIBRATION_REQUIRED) MarshalBinary

func (e GIMBAL_AXIS_CALIBRATION_REQUIRED) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GIMBAL_AXIS_CALIBRATION_REQUIRED) String

func (*GIMBAL_AXIS_CALIBRATION_REQUIRED) UnmarshalBinary

func (e *GIMBAL_AXIS_CALIBRATION_REQUIRED) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GIMBAL_AXIS_CALIBRATION_STATUS

type GIMBAL_AXIS_CALIBRATION_STATUS int

GIMBAL_AXIS_CALIBRATION_STATUS type

const (
	// GIMBAL_AXIS_CALIBRATION_STATUS_IN_PROGRESS enum. Axis calibration is in progress
	GIMBAL_AXIS_CALIBRATION_STATUS_IN_PROGRESS GIMBAL_AXIS_CALIBRATION_STATUS = 0
	// GIMBAL_AXIS_CALIBRATION_STATUS_SUCCEEDED enum. Axis calibration succeeded
	GIMBAL_AXIS_CALIBRATION_STATUS_SUCCEEDED GIMBAL_AXIS_CALIBRATION_STATUS = 1
	// GIMBAL_AXIS_CALIBRATION_STATUS_FAILED enum. Axis calibration failed
	GIMBAL_AXIS_CALIBRATION_STATUS_FAILED GIMBAL_AXIS_CALIBRATION_STATUS = 2
)

func (GIMBAL_AXIS_CALIBRATION_STATUS) Bitmask

Bitmask return string representetion of intersects GIMBAL_AXIS_CALIBRATION_STATUS enums

func (GIMBAL_AXIS_CALIBRATION_STATUS) MarshalBinary

func (e GIMBAL_AXIS_CALIBRATION_STATUS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GIMBAL_AXIS_CALIBRATION_STATUS) String

func (*GIMBAL_AXIS_CALIBRATION_STATUS) UnmarshalBinary

func (e *GIMBAL_AXIS_CALIBRATION_STATUS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GIMBAL_DEVICE_CAP_FLAGS

type GIMBAL_DEVICE_CAP_FLAGS int

GIMBAL_DEVICE_CAP_FLAGS type. Gimbal device (low level) capability flags (bitmap)

const (
	// GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT enum. Gimbal device supports a retracted position
	GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT GIMBAL_DEVICE_CAP_FLAGS = 1
	// GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL enum. Gimbal device supports a horizontal, forward looking position, stabilized
	GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL GIMBAL_DEVICE_CAP_FLAGS = 2
	// GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS enum. Gimbal device supports rotating around roll axis
	GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS GIMBAL_DEVICE_CAP_FLAGS = 4
	// GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW enum. Gimbal device supports to follow a roll angle relative to the vehicle
	GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW GIMBAL_DEVICE_CAP_FLAGS = 8
	// GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK enum. Gimbal device supports locking to an roll angle (generally that's the default with roll stabilized)
	GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK GIMBAL_DEVICE_CAP_FLAGS = 16
	// GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS enum. Gimbal device supports rotating around pitch axis
	GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS GIMBAL_DEVICE_CAP_FLAGS = 32
	// GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW enum. Gimbal device supports to follow a pitch angle relative to the vehicle
	GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW GIMBAL_DEVICE_CAP_FLAGS = 64
	// GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK enum. Gimbal device supports locking to an pitch angle (generally that's the default with pitch stabilized)
	GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK GIMBAL_DEVICE_CAP_FLAGS = 128
	// GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS enum. Gimbal device supports rotating around yaw axis
	GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS GIMBAL_DEVICE_CAP_FLAGS = 256
	// GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW enum. Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default)
	GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW GIMBAL_DEVICE_CAP_FLAGS = 512
	// GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK enum. Gimbal device supports locking to an absolute heading (often this is an option available)
	GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK GIMBAL_DEVICE_CAP_FLAGS = 1024
	// GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW enum. Gimbal device supports yawing/panning infinetely (e.g. using slip disk)
	GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW GIMBAL_DEVICE_CAP_FLAGS = 2048
)

func (GIMBAL_DEVICE_CAP_FLAGS) Bitmask

func (e GIMBAL_DEVICE_CAP_FLAGS) Bitmask() string

Bitmask return string representetion of intersects GIMBAL_DEVICE_CAP_FLAGS enums

func (GIMBAL_DEVICE_CAP_FLAGS) MarshalBinary

func (e GIMBAL_DEVICE_CAP_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GIMBAL_DEVICE_CAP_FLAGS) String

func (e GIMBAL_DEVICE_CAP_FLAGS) String() string

func (*GIMBAL_DEVICE_CAP_FLAGS) UnmarshalBinary

func (e *GIMBAL_DEVICE_CAP_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GIMBAL_DEVICE_ERROR_FLAGS

type GIMBAL_DEVICE_ERROR_FLAGS int

GIMBAL_DEVICE_ERROR_FLAGS type. Gimbal device (low level) error flags (bitmap, 0 means no error)

const (
	// GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT enum. Gimbal device is limited by hardware roll limit
	GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT GIMBAL_DEVICE_ERROR_FLAGS = 1
	// GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT enum. Gimbal device is limited by hardware pitch limit
	GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT GIMBAL_DEVICE_ERROR_FLAGS = 2
	// GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT enum. Gimbal device is limited by hardware yaw limit
	GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT GIMBAL_DEVICE_ERROR_FLAGS = 4
	// GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR enum. There is an error with the gimbal encoders
	GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR GIMBAL_DEVICE_ERROR_FLAGS = 8
	// GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR enum. There is an error with the gimbal power source
	GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR GIMBAL_DEVICE_ERROR_FLAGS = 16
	// GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR enum. There is an error with the gimbal motor's
	GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR GIMBAL_DEVICE_ERROR_FLAGS = 32
	// GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR enum. There is an error with the gimbal's software
	GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR GIMBAL_DEVICE_ERROR_FLAGS = 64
	// GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR enum. There is an error with the gimbal's communication
	GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR GIMBAL_DEVICE_ERROR_FLAGS = 128
	// GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING enum. Gimbal is currently calibrating
	GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING GIMBAL_DEVICE_ERROR_FLAGS = 256
)

func (GIMBAL_DEVICE_ERROR_FLAGS) Bitmask

func (e GIMBAL_DEVICE_ERROR_FLAGS) Bitmask() string

Bitmask return string representetion of intersects GIMBAL_DEVICE_ERROR_FLAGS enums

func (GIMBAL_DEVICE_ERROR_FLAGS) MarshalBinary

func (e GIMBAL_DEVICE_ERROR_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GIMBAL_DEVICE_ERROR_FLAGS) String

func (e GIMBAL_DEVICE_ERROR_FLAGS) String() string

func (*GIMBAL_DEVICE_ERROR_FLAGS) UnmarshalBinary

func (e *GIMBAL_DEVICE_ERROR_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GIMBAL_DEVICE_FLAGS

type GIMBAL_DEVICE_FLAGS int

GIMBAL_DEVICE_FLAGS type. Flags for gimbal device (lower level) operation.

const (
	// GIMBAL_DEVICE_FLAGS_RETRACT enum. Set to retracted safe position (no stabilization), takes presedence over all other flags
	GIMBAL_DEVICE_FLAGS_RETRACT GIMBAL_DEVICE_FLAGS = 1
	// GIMBAL_DEVICE_FLAGS_NEUTRAL enum. Set to neutral position (horizontal, forward looking, with stabiliziation), takes presedence over all other flags except RETRACT
	GIMBAL_DEVICE_FLAGS_NEUTRAL GIMBAL_DEVICE_FLAGS = 2
	// GIMBAL_DEVICE_FLAGS_ROLL_LOCK enum. Lock roll angle to absolute angle relative to horizon (not relative to drone). This is generally the default with a stabilizing gimbal
	GIMBAL_DEVICE_FLAGS_ROLL_LOCK GIMBAL_DEVICE_FLAGS = 4
	// GIMBAL_DEVICE_FLAGS_PITCH_LOCK enum. Lock pitch angle to absolute angle relative to horizon (not relative to drone). This is generally the default
	GIMBAL_DEVICE_FLAGS_PITCH_LOCK GIMBAL_DEVICE_FLAGS = 8
	// GIMBAL_DEVICE_FLAGS_YAW_LOCK enum. Lock yaw angle to absolute angle relative to North (not relative to drone). If this flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute). If this flag is not set, the quaternion frame is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle)
	GIMBAL_DEVICE_FLAGS_YAW_LOCK GIMBAL_DEVICE_FLAGS = 16
)

func (GIMBAL_DEVICE_FLAGS) Bitmask

func (e GIMBAL_DEVICE_FLAGS) Bitmask() string

Bitmask return string representetion of intersects GIMBAL_DEVICE_FLAGS enums

func (GIMBAL_DEVICE_FLAGS) MarshalBinary

func (e GIMBAL_DEVICE_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GIMBAL_DEVICE_FLAGS) String

func (e GIMBAL_DEVICE_FLAGS) String() string

func (*GIMBAL_DEVICE_FLAGS) UnmarshalBinary

func (e *GIMBAL_DEVICE_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GIMBAL_MANAGER_CAP_FLAGS

type GIMBAL_MANAGER_CAP_FLAGS int

GIMBAL_MANAGER_CAP_FLAGS type. Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS which are identical with GIMBAL_DEVICE_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags.

const (
	// GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT enum. Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT
	GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT GIMBAL_MANAGER_CAP_FLAGS = 1
	// GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL enum. Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL
	GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL GIMBAL_MANAGER_CAP_FLAGS = 2
	// GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS enum. Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS
	GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS GIMBAL_MANAGER_CAP_FLAGS = 4
	// GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW enum. Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW
	GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW GIMBAL_MANAGER_CAP_FLAGS = 8
	// GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK enum. Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK
	GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK GIMBAL_MANAGER_CAP_FLAGS = 16
	// GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS enum. Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS
	GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS GIMBAL_MANAGER_CAP_FLAGS = 32
	// GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW enum. Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW
	GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW GIMBAL_MANAGER_CAP_FLAGS = 64
	// GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK enum. Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK
	GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK GIMBAL_MANAGER_CAP_FLAGS = 128
	// GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS enum. Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS
	GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS GIMBAL_MANAGER_CAP_FLAGS = 256
	// GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW enum. Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW
	GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW GIMBAL_MANAGER_CAP_FLAGS = 512
	// GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK enum. Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK
	GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK GIMBAL_MANAGER_CAP_FLAGS = 1024
	// GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW enum. Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW
	GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW GIMBAL_MANAGER_CAP_FLAGS = 2048
	// GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL enum. Gimbal manager supports to point to a local position
	GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL GIMBAL_MANAGER_CAP_FLAGS = 65536
	// GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL enum. Gimbal manager supports to point to a global latitude, longitude, altitude position
	GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL GIMBAL_MANAGER_CAP_FLAGS = 131072
)

func (GIMBAL_MANAGER_CAP_FLAGS) Bitmask

func (e GIMBAL_MANAGER_CAP_FLAGS) Bitmask() string

Bitmask return string representetion of intersects GIMBAL_MANAGER_CAP_FLAGS enums

func (GIMBAL_MANAGER_CAP_FLAGS) MarshalBinary

func (e GIMBAL_MANAGER_CAP_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GIMBAL_MANAGER_CAP_FLAGS) String

func (e GIMBAL_MANAGER_CAP_FLAGS) String() string

func (*GIMBAL_MANAGER_CAP_FLAGS) UnmarshalBinary

func (e *GIMBAL_MANAGER_CAP_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GIMBAL_MANAGER_FLAGS

type GIMBAL_MANAGER_FLAGS int

GIMBAL_MANAGER_FLAGS type. Flags for high level gimbal manager operation The first 16 bytes are identical to the GIMBAL_DEVICE_FLAGS.

const (
	// GIMBAL_MANAGER_FLAGS_RETRACT enum. Based on GIMBAL_DEVICE_FLAGS_RETRACT
	GIMBAL_MANAGER_FLAGS_RETRACT GIMBAL_MANAGER_FLAGS = 1
	// GIMBAL_MANAGER_FLAGS_NEUTRAL enum. Based on GIMBAL_DEVICE_FLAGS_NEUTRAL
	GIMBAL_MANAGER_FLAGS_NEUTRAL GIMBAL_MANAGER_FLAGS = 2
	// GIMBAL_MANAGER_FLAGS_ROLL_LOCK enum. Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK
	GIMBAL_MANAGER_FLAGS_ROLL_LOCK GIMBAL_MANAGER_FLAGS = 4
	// GIMBAL_MANAGER_FLAGS_PITCH_LOCK enum. Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK
	GIMBAL_MANAGER_FLAGS_PITCH_LOCK GIMBAL_MANAGER_FLAGS = 8
	// GIMBAL_MANAGER_FLAGS_YAW_LOCK enum. Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK
	GIMBAL_MANAGER_FLAGS_YAW_LOCK GIMBAL_MANAGER_FLAGS = 16
)

func (GIMBAL_MANAGER_FLAGS) Bitmask

func (e GIMBAL_MANAGER_FLAGS) Bitmask() string

Bitmask return string representetion of intersects GIMBAL_MANAGER_FLAGS enums

func (GIMBAL_MANAGER_FLAGS) MarshalBinary

func (e GIMBAL_MANAGER_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GIMBAL_MANAGER_FLAGS) String

func (e GIMBAL_MANAGER_FLAGS) String() string

func (*GIMBAL_MANAGER_FLAGS) UnmarshalBinary

func (e *GIMBAL_MANAGER_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_BURST_RATE

type GOPRO_BURST_RATE int

GOPRO_BURST_RATE type

const (
	// GOPRO_BURST_RATE_3_IN_1_SECOND enum. 3 Shots / 1 Second
	GOPRO_BURST_RATE_3_IN_1_SECOND GOPRO_BURST_RATE = 0
	// GOPRO_BURST_RATE_5_IN_1_SECOND enum. 5 Shots / 1 Second
	GOPRO_BURST_RATE_5_IN_1_SECOND GOPRO_BURST_RATE = 1
	// GOPRO_BURST_RATE_10_IN_1_SECOND enum. 10 Shots / 1 Second
	GOPRO_BURST_RATE_10_IN_1_SECOND GOPRO_BURST_RATE = 2
	// GOPRO_BURST_RATE_10_IN_2_SECOND enum. 10 Shots / 2 Second
	GOPRO_BURST_RATE_10_IN_2_SECOND GOPRO_BURST_RATE = 3
	// GOPRO_BURST_RATE_10_IN_3_SECOND enum. 10 Shots / 3 Second (Hero 4 Only)
	GOPRO_BURST_RATE_10_IN_3_SECOND GOPRO_BURST_RATE = 4
	// GOPRO_BURST_RATE_30_IN_1_SECOND enum. 30 Shots / 1 Second
	GOPRO_BURST_RATE_30_IN_1_SECOND GOPRO_BURST_RATE = 5
	// GOPRO_BURST_RATE_30_IN_2_SECOND enum. 30 Shots / 2 Second
	GOPRO_BURST_RATE_30_IN_2_SECOND GOPRO_BURST_RATE = 6
	// GOPRO_BURST_RATE_30_IN_3_SECOND enum. 30 Shots / 3 Second
	GOPRO_BURST_RATE_30_IN_3_SECOND GOPRO_BURST_RATE = 7
	// GOPRO_BURST_RATE_30_IN_6_SECOND enum. 30 Shots / 6 Second
	GOPRO_BURST_RATE_30_IN_6_SECOND GOPRO_BURST_RATE = 8
)

func (GOPRO_BURST_RATE) Bitmask

func (e GOPRO_BURST_RATE) Bitmask() string

Bitmask return string representetion of intersects GOPRO_BURST_RATE enums

func (GOPRO_BURST_RATE) MarshalBinary

func (e GOPRO_BURST_RATE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_BURST_RATE) String

func (e GOPRO_BURST_RATE) String() string

func (*GOPRO_BURST_RATE) UnmarshalBinary

func (e *GOPRO_BURST_RATE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_CAPTURE_MODE

type GOPRO_CAPTURE_MODE int

GOPRO_CAPTURE_MODE type

const (
	// GOPRO_CAPTURE_MODE_VIDEO enum. Video mode
	GOPRO_CAPTURE_MODE_VIDEO GOPRO_CAPTURE_MODE = 0
	// GOPRO_CAPTURE_MODE_PHOTO enum. Photo mode
	GOPRO_CAPTURE_MODE_PHOTO GOPRO_CAPTURE_MODE = 1
	// GOPRO_CAPTURE_MODE_BURST enum. Burst mode, Hero 3+ only
	GOPRO_CAPTURE_MODE_BURST GOPRO_CAPTURE_MODE = 2
	// GOPRO_CAPTURE_MODE_TIME_LAPSE enum. Time lapse mode, Hero 3+ only
	GOPRO_CAPTURE_MODE_TIME_LAPSE GOPRO_CAPTURE_MODE = 3
	// GOPRO_CAPTURE_MODE_MULTI_SHOT enum. Multi shot mode, Hero 4 only
	GOPRO_CAPTURE_MODE_MULTI_SHOT GOPRO_CAPTURE_MODE = 4
	// GOPRO_CAPTURE_MODE_PLAYBACK enum. Playback mode, Hero 4 only, silver only except when LCD or HDMI is connected to black
	GOPRO_CAPTURE_MODE_PLAYBACK GOPRO_CAPTURE_MODE = 5
	// GOPRO_CAPTURE_MODE_SETUP enum. Playback mode, Hero 4 only
	GOPRO_CAPTURE_MODE_SETUP GOPRO_CAPTURE_MODE = 6
	// GOPRO_CAPTURE_MODE_UNKNOWN enum. Mode not yet known
	GOPRO_CAPTURE_MODE_UNKNOWN GOPRO_CAPTURE_MODE = 255
)

func (GOPRO_CAPTURE_MODE) Bitmask

func (e GOPRO_CAPTURE_MODE) Bitmask() string

Bitmask return string representetion of intersects GOPRO_CAPTURE_MODE enums

func (GOPRO_CAPTURE_MODE) MarshalBinary

func (e GOPRO_CAPTURE_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_CAPTURE_MODE) String

func (e GOPRO_CAPTURE_MODE) String() string

func (*GOPRO_CAPTURE_MODE) UnmarshalBinary

func (e *GOPRO_CAPTURE_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_CHARGING

type GOPRO_CHARGING int

GOPRO_CHARGING type

const (
	// GOPRO_CHARGING_DISABLED enum. Charging disabled
	GOPRO_CHARGING_DISABLED GOPRO_CHARGING = 0
	// GOPRO_CHARGING_ENABLED enum. Charging enabled
	GOPRO_CHARGING_ENABLED GOPRO_CHARGING = 1
)

func (GOPRO_CHARGING) Bitmask

func (e GOPRO_CHARGING) Bitmask() string

Bitmask return string representetion of intersects GOPRO_CHARGING enums

func (GOPRO_CHARGING) MarshalBinary

func (e GOPRO_CHARGING) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_CHARGING) String

func (e GOPRO_CHARGING) String() string

func (*GOPRO_CHARGING) UnmarshalBinary

func (e *GOPRO_CHARGING) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_COMMAND

type GOPRO_COMMAND int

GOPRO_COMMAND type

const (
	// GOPRO_COMMAND_POWER enum. (Get/Set)
	GOPRO_COMMAND_POWER GOPRO_COMMAND = 0
	// GOPRO_COMMAND_CAPTURE_MODE enum. (Get/Set)
	GOPRO_COMMAND_CAPTURE_MODE GOPRO_COMMAND = 1
	// GOPRO_COMMAND_SHUTTER enum. (___/Set)
	GOPRO_COMMAND_SHUTTER GOPRO_COMMAND = 2
	// GOPRO_COMMAND_BATTERY enum. (Get/___)
	GOPRO_COMMAND_BATTERY GOPRO_COMMAND = 3
	// GOPRO_COMMAND_MODEL enum. (Get/___)
	GOPRO_COMMAND_MODEL GOPRO_COMMAND = 4
	// GOPRO_COMMAND_VIDEO_SETTINGS enum. (Get/Set)
	GOPRO_COMMAND_VIDEO_SETTINGS GOPRO_COMMAND = 5
	// GOPRO_COMMAND_LOW_LIGHT enum. (Get/Set)
	GOPRO_COMMAND_LOW_LIGHT GOPRO_COMMAND = 6
	// GOPRO_COMMAND_PHOTO_RESOLUTION enum. (Get/Set)
	GOPRO_COMMAND_PHOTO_RESOLUTION GOPRO_COMMAND = 7
	// GOPRO_COMMAND_PHOTO_BURST_RATE enum. (Get/Set)
	GOPRO_COMMAND_PHOTO_BURST_RATE GOPRO_COMMAND = 8
	// GOPRO_COMMAND_PROTUNE enum. (Get/Set)
	GOPRO_COMMAND_PROTUNE GOPRO_COMMAND = 9
	// GOPRO_COMMAND_PROTUNE_WHITE_BALANCE enum. (Get/Set) Hero 3+ Only
	GOPRO_COMMAND_PROTUNE_WHITE_BALANCE GOPRO_COMMAND = 10
	// GOPRO_COMMAND_PROTUNE_COLOUR enum. (Get/Set) Hero 3+ Only
	GOPRO_COMMAND_PROTUNE_COLOUR GOPRO_COMMAND = 11
	// GOPRO_COMMAND_PROTUNE_GAIN enum. (Get/Set) Hero 3+ Only
	GOPRO_COMMAND_PROTUNE_GAIN GOPRO_COMMAND = 12
	// GOPRO_COMMAND_PROTUNE_SHARPNESS enum. (Get/Set) Hero 3+ Only
	GOPRO_COMMAND_PROTUNE_SHARPNESS GOPRO_COMMAND = 13
	// GOPRO_COMMAND_PROTUNE_EXPOSURE enum. (Get/Set) Hero 3+ Only
	GOPRO_COMMAND_PROTUNE_EXPOSURE GOPRO_COMMAND = 14
	// GOPRO_COMMAND_TIME enum. (Get/Set)
	GOPRO_COMMAND_TIME GOPRO_COMMAND = 15
	// GOPRO_COMMAND_CHARGING enum. (Get/Set)
	GOPRO_COMMAND_CHARGING GOPRO_COMMAND = 16
)

func (GOPRO_COMMAND) Bitmask

func (e GOPRO_COMMAND) Bitmask() string

Bitmask return string representetion of intersects GOPRO_COMMAND enums

func (GOPRO_COMMAND) MarshalBinary

func (e GOPRO_COMMAND) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_COMMAND) String

func (e GOPRO_COMMAND) String() string

func (*GOPRO_COMMAND) UnmarshalBinary

func (e *GOPRO_COMMAND) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_FIELD_OF_VIEW

type GOPRO_FIELD_OF_VIEW int

GOPRO_FIELD_OF_VIEW type

const (
	// GOPRO_FIELD_OF_VIEW_WIDE enum. 0x00: Wide
	GOPRO_FIELD_OF_VIEW_WIDE GOPRO_FIELD_OF_VIEW = 0
	// GOPRO_FIELD_OF_VIEW_MEDIUM enum. 0x01: Medium
	GOPRO_FIELD_OF_VIEW_MEDIUM GOPRO_FIELD_OF_VIEW = 1
	// GOPRO_FIELD_OF_VIEW_NARROW enum. 0x02: Narrow
	GOPRO_FIELD_OF_VIEW_NARROW GOPRO_FIELD_OF_VIEW = 2
)

func (GOPRO_FIELD_OF_VIEW) Bitmask

func (e GOPRO_FIELD_OF_VIEW) Bitmask() string

Bitmask return string representetion of intersects GOPRO_FIELD_OF_VIEW enums

func (GOPRO_FIELD_OF_VIEW) MarshalBinary

func (e GOPRO_FIELD_OF_VIEW) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_FIELD_OF_VIEW) String

func (e GOPRO_FIELD_OF_VIEW) String() string

func (*GOPRO_FIELD_OF_VIEW) UnmarshalBinary

func (e *GOPRO_FIELD_OF_VIEW) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_FRAME_RATE

type GOPRO_FRAME_RATE int

GOPRO_FRAME_RATE type

const (
	// GOPRO_FRAME_RATE_12 enum. 12 FPS
	GOPRO_FRAME_RATE_12 GOPRO_FRAME_RATE = 0
	// GOPRO_FRAME_RATE_15 enum. 15 FPS
	GOPRO_FRAME_RATE_15 GOPRO_FRAME_RATE = 1
	// GOPRO_FRAME_RATE_24 enum. 24 FPS
	GOPRO_FRAME_RATE_24 GOPRO_FRAME_RATE = 2
	// GOPRO_FRAME_RATE_25 enum. 25 FPS
	GOPRO_FRAME_RATE_25 GOPRO_FRAME_RATE = 3
	// GOPRO_FRAME_RATE_30 enum. 30 FPS
	GOPRO_FRAME_RATE_30 GOPRO_FRAME_RATE = 4
	// GOPRO_FRAME_RATE_48 enum. 48 FPS
	GOPRO_FRAME_RATE_48 GOPRO_FRAME_RATE = 5
	// GOPRO_FRAME_RATE_50 enum. 50 FPS
	GOPRO_FRAME_RATE_50 GOPRO_FRAME_RATE = 6
	// GOPRO_FRAME_RATE_60 enum. 60 FPS
	GOPRO_FRAME_RATE_60 GOPRO_FRAME_RATE = 7
	// GOPRO_FRAME_RATE_80 enum. 80 FPS
	GOPRO_FRAME_RATE_80 GOPRO_FRAME_RATE = 8
	// GOPRO_FRAME_RATE_90 enum. 90 FPS
	GOPRO_FRAME_RATE_90 GOPRO_FRAME_RATE = 9
	// GOPRO_FRAME_RATE_100 enum. 100 FPS
	GOPRO_FRAME_RATE_100 GOPRO_FRAME_RATE = 10
	// GOPRO_FRAME_RATE_120 enum. 120 FPS
	GOPRO_FRAME_RATE_120 GOPRO_FRAME_RATE = 11
	// GOPRO_FRAME_RATE_240 enum. 240 FPS
	GOPRO_FRAME_RATE_240 GOPRO_FRAME_RATE = 12
	// GOPRO_FRAME_RATE_12_5 enum. 12.5 FPS
	GOPRO_FRAME_RATE_12_5 GOPRO_FRAME_RATE = 13
)

func (GOPRO_FRAME_RATE) Bitmask

func (e GOPRO_FRAME_RATE) Bitmask() string

Bitmask return string representetion of intersects GOPRO_FRAME_RATE enums

func (GOPRO_FRAME_RATE) MarshalBinary

func (e GOPRO_FRAME_RATE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_FRAME_RATE) String

func (e GOPRO_FRAME_RATE) String() string

func (*GOPRO_FRAME_RATE) UnmarshalBinary

func (e *GOPRO_FRAME_RATE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_HEARTBEAT_FLAGS

type GOPRO_HEARTBEAT_FLAGS int

GOPRO_HEARTBEAT_FLAGS type

const (
	// GOPRO_FLAG_RECORDING enum. GoPro is currently recording
	GOPRO_FLAG_RECORDING GOPRO_HEARTBEAT_FLAGS = 1
)

func (GOPRO_HEARTBEAT_FLAGS) Bitmask

func (e GOPRO_HEARTBEAT_FLAGS) Bitmask() string

Bitmask return string representetion of intersects GOPRO_HEARTBEAT_FLAGS enums

func (GOPRO_HEARTBEAT_FLAGS) MarshalBinary

func (e GOPRO_HEARTBEAT_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_HEARTBEAT_FLAGS) String

func (e GOPRO_HEARTBEAT_FLAGS) String() string

func (*GOPRO_HEARTBEAT_FLAGS) UnmarshalBinary

func (e *GOPRO_HEARTBEAT_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_HEARTBEAT_STATUS

type GOPRO_HEARTBEAT_STATUS int

GOPRO_HEARTBEAT_STATUS type

const (
	// GOPRO_HEARTBEAT_STATUS_DISCONNECTED enum. No GoPro connected
	GOPRO_HEARTBEAT_STATUS_DISCONNECTED GOPRO_HEARTBEAT_STATUS = 0
	// GOPRO_HEARTBEAT_STATUS_INCOMPATIBLE enum. The detected GoPro is not HeroBus compatible
	GOPRO_HEARTBEAT_STATUS_INCOMPATIBLE GOPRO_HEARTBEAT_STATUS = 1
	// GOPRO_HEARTBEAT_STATUS_CONNECTED enum. A HeroBus compatible GoPro is connected
	GOPRO_HEARTBEAT_STATUS_CONNECTED GOPRO_HEARTBEAT_STATUS = 2
	// GOPRO_HEARTBEAT_STATUS_ERROR enum. An unrecoverable error was encountered with the connected GoPro, it may require a power cycle
	GOPRO_HEARTBEAT_STATUS_ERROR GOPRO_HEARTBEAT_STATUS = 3
)

func (GOPRO_HEARTBEAT_STATUS) Bitmask

func (e GOPRO_HEARTBEAT_STATUS) Bitmask() string

Bitmask return string representetion of intersects GOPRO_HEARTBEAT_STATUS enums

func (GOPRO_HEARTBEAT_STATUS) MarshalBinary

func (e GOPRO_HEARTBEAT_STATUS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_HEARTBEAT_STATUS) String

func (e GOPRO_HEARTBEAT_STATUS) String() string

func (*GOPRO_HEARTBEAT_STATUS) UnmarshalBinary

func (e *GOPRO_HEARTBEAT_STATUS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_MODEL

type GOPRO_MODEL int

GOPRO_MODEL type

const (
	// GOPRO_MODEL_UNKNOWN enum. Unknown gopro model
	GOPRO_MODEL_UNKNOWN GOPRO_MODEL = 0
	// GOPRO_MODEL_HERO_3_PLUS_SILVER enum. Hero 3+ Silver (HeroBus not supported by GoPro)
	GOPRO_MODEL_HERO_3_PLUS_SILVER GOPRO_MODEL = 1
	// GOPRO_MODEL_HERO_3_PLUS_BLACK enum. Hero 3+ Black
	GOPRO_MODEL_HERO_3_PLUS_BLACK GOPRO_MODEL = 2
	// GOPRO_MODEL_HERO_4_SILVER enum. Hero 4 Silver
	GOPRO_MODEL_HERO_4_SILVER GOPRO_MODEL = 3
	// GOPRO_MODEL_HERO_4_BLACK enum. Hero 4 Black
	GOPRO_MODEL_HERO_4_BLACK GOPRO_MODEL = 4
)

func (GOPRO_MODEL) Bitmask

func (e GOPRO_MODEL) Bitmask() string

Bitmask return string representetion of intersects GOPRO_MODEL enums

func (GOPRO_MODEL) MarshalBinary

func (e GOPRO_MODEL) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_MODEL) String

func (e GOPRO_MODEL) String() string

func (*GOPRO_MODEL) UnmarshalBinary

func (e *GOPRO_MODEL) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_PHOTO_RESOLUTION

type GOPRO_PHOTO_RESOLUTION int

GOPRO_PHOTO_RESOLUTION type

const (
	// GOPRO_PHOTO_RESOLUTION_5MP_MEDIUM enum. 5MP Medium
	GOPRO_PHOTO_RESOLUTION_5MP_MEDIUM GOPRO_PHOTO_RESOLUTION = 0
	// GOPRO_PHOTO_RESOLUTION_7MP_MEDIUM enum. 7MP Medium
	GOPRO_PHOTO_RESOLUTION_7MP_MEDIUM GOPRO_PHOTO_RESOLUTION = 1
	// GOPRO_PHOTO_RESOLUTION_7MP_WIDE enum. 7MP Wide
	GOPRO_PHOTO_RESOLUTION_7MP_WIDE GOPRO_PHOTO_RESOLUTION = 2
	// GOPRO_PHOTO_RESOLUTION_10MP_WIDE enum. 10MP Wide
	GOPRO_PHOTO_RESOLUTION_10MP_WIDE GOPRO_PHOTO_RESOLUTION = 3
	// GOPRO_PHOTO_RESOLUTION_12MP_WIDE enum. 12MP Wide
	GOPRO_PHOTO_RESOLUTION_12MP_WIDE GOPRO_PHOTO_RESOLUTION = 4
)

func (GOPRO_PHOTO_RESOLUTION) Bitmask

func (e GOPRO_PHOTO_RESOLUTION) Bitmask() string

Bitmask return string representetion of intersects GOPRO_PHOTO_RESOLUTION enums

func (GOPRO_PHOTO_RESOLUTION) MarshalBinary

func (e GOPRO_PHOTO_RESOLUTION) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_PHOTO_RESOLUTION) String

func (e GOPRO_PHOTO_RESOLUTION) String() string

func (*GOPRO_PHOTO_RESOLUTION) UnmarshalBinary

func (e *GOPRO_PHOTO_RESOLUTION) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_PROTUNE_COLOUR

type GOPRO_PROTUNE_COLOUR int

GOPRO_PROTUNE_COLOUR type

const (
	// GOPRO_PROTUNE_COLOUR_STANDARD enum. Auto
	GOPRO_PROTUNE_COLOUR_STANDARD GOPRO_PROTUNE_COLOUR = 0
	// GOPRO_PROTUNE_COLOUR_NEUTRAL enum. Neutral
	GOPRO_PROTUNE_COLOUR_NEUTRAL GOPRO_PROTUNE_COLOUR = 1
)

func (GOPRO_PROTUNE_COLOUR) Bitmask

func (e GOPRO_PROTUNE_COLOUR) Bitmask() string

Bitmask return string representetion of intersects GOPRO_PROTUNE_COLOUR enums

func (GOPRO_PROTUNE_COLOUR) MarshalBinary

func (e GOPRO_PROTUNE_COLOUR) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_PROTUNE_COLOUR) String

func (e GOPRO_PROTUNE_COLOUR) String() string

func (*GOPRO_PROTUNE_COLOUR) UnmarshalBinary

func (e *GOPRO_PROTUNE_COLOUR) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_PROTUNE_EXPOSURE

type GOPRO_PROTUNE_EXPOSURE int

GOPRO_PROTUNE_EXPOSURE type

const (
	// GOPRO_PROTUNE_EXPOSURE_NEG_5_0 enum. -5.0 EV (Hero 3+ Only)
	GOPRO_PROTUNE_EXPOSURE_NEG_5_0 GOPRO_PROTUNE_EXPOSURE = 0
	// GOPRO_PROTUNE_EXPOSURE_NEG_4_5 enum. -4.5 EV (Hero 3+ Only)
	GOPRO_PROTUNE_EXPOSURE_NEG_4_5 GOPRO_PROTUNE_EXPOSURE = 1
	// GOPRO_PROTUNE_EXPOSURE_NEG_4_0 enum. -4.0 EV (Hero 3+ Only)
	GOPRO_PROTUNE_EXPOSURE_NEG_4_0 GOPRO_PROTUNE_EXPOSURE = 2
	// GOPRO_PROTUNE_EXPOSURE_NEG_3_5 enum. -3.5 EV (Hero 3+ Only)
	GOPRO_PROTUNE_EXPOSURE_NEG_3_5 GOPRO_PROTUNE_EXPOSURE = 3
	// GOPRO_PROTUNE_EXPOSURE_NEG_3_0 enum. -3.0 EV (Hero 3+ Only)
	GOPRO_PROTUNE_EXPOSURE_NEG_3_0 GOPRO_PROTUNE_EXPOSURE = 4
	// GOPRO_PROTUNE_EXPOSURE_NEG_2_5 enum. -2.5 EV (Hero 3+ Only)
	GOPRO_PROTUNE_EXPOSURE_NEG_2_5 GOPRO_PROTUNE_EXPOSURE = 5
	// GOPRO_PROTUNE_EXPOSURE_NEG_2_0 enum. -2.0 EV
	GOPRO_PROTUNE_EXPOSURE_NEG_2_0 GOPRO_PROTUNE_EXPOSURE = 6
	// GOPRO_PROTUNE_EXPOSURE_NEG_1_5 enum. -1.5 EV
	GOPRO_PROTUNE_EXPOSURE_NEG_1_5 GOPRO_PROTUNE_EXPOSURE = 7
	// GOPRO_PROTUNE_EXPOSURE_NEG_1_0 enum. -1.0 EV
	GOPRO_PROTUNE_EXPOSURE_NEG_1_0 GOPRO_PROTUNE_EXPOSURE = 8
	// GOPRO_PROTUNE_EXPOSURE_NEG_0_5 enum. -0.5 EV
	GOPRO_PROTUNE_EXPOSURE_NEG_0_5 GOPRO_PROTUNE_EXPOSURE = 9
	// GOPRO_PROTUNE_EXPOSURE_ZERO enum. 0.0 EV
	GOPRO_PROTUNE_EXPOSURE_ZERO GOPRO_PROTUNE_EXPOSURE = 10
	// GOPRO_PROTUNE_EXPOSURE_POS_0_5 enum. +0.5 EV
	GOPRO_PROTUNE_EXPOSURE_POS_0_5 GOPRO_PROTUNE_EXPOSURE = 11
	// GOPRO_PROTUNE_EXPOSURE_POS_1_0 enum. +1.0 EV
	GOPRO_PROTUNE_EXPOSURE_POS_1_0 GOPRO_PROTUNE_EXPOSURE = 12
	// GOPRO_PROTUNE_EXPOSURE_POS_1_5 enum. +1.5 EV
	GOPRO_PROTUNE_EXPOSURE_POS_1_5 GOPRO_PROTUNE_EXPOSURE = 13
	// GOPRO_PROTUNE_EXPOSURE_POS_2_0 enum. +2.0 EV
	GOPRO_PROTUNE_EXPOSURE_POS_2_0 GOPRO_PROTUNE_EXPOSURE = 14
	// GOPRO_PROTUNE_EXPOSURE_POS_2_5 enum. +2.5 EV (Hero 3+ Only)
	GOPRO_PROTUNE_EXPOSURE_POS_2_5 GOPRO_PROTUNE_EXPOSURE = 15
	// GOPRO_PROTUNE_EXPOSURE_POS_3_0 enum. +3.0 EV (Hero 3+ Only)
	GOPRO_PROTUNE_EXPOSURE_POS_3_0 GOPRO_PROTUNE_EXPOSURE = 16
	// GOPRO_PROTUNE_EXPOSURE_POS_3_5 enum. +3.5 EV (Hero 3+ Only)
	GOPRO_PROTUNE_EXPOSURE_POS_3_5 GOPRO_PROTUNE_EXPOSURE = 17
	// GOPRO_PROTUNE_EXPOSURE_POS_4_0 enum. +4.0 EV (Hero 3+ Only)
	GOPRO_PROTUNE_EXPOSURE_POS_4_0 GOPRO_PROTUNE_EXPOSURE = 18
	// GOPRO_PROTUNE_EXPOSURE_POS_4_5 enum. +4.5 EV (Hero 3+ Only)
	GOPRO_PROTUNE_EXPOSURE_POS_4_5 GOPRO_PROTUNE_EXPOSURE = 19
	// GOPRO_PROTUNE_EXPOSURE_POS_5_0 enum. +5.0 EV (Hero 3+ Only)
	GOPRO_PROTUNE_EXPOSURE_POS_5_0 GOPRO_PROTUNE_EXPOSURE = 20
)

func (GOPRO_PROTUNE_EXPOSURE) Bitmask

func (e GOPRO_PROTUNE_EXPOSURE) Bitmask() string

Bitmask return string representetion of intersects GOPRO_PROTUNE_EXPOSURE enums

func (GOPRO_PROTUNE_EXPOSURE) MarshalBinary

func (e GOPRO_PROTUNE_EXPOSURE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_PROTUNE_EXPOSURE) String

func (e GOPRO_PROTUNE_EXPOSURE) String() string

func (*GOPRO_PROTUNE_EXPOSURE) UnmarshalBinary

func (e *GOPRO_PROTUNE_EXPOSURE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_PROTUNE_GAIN

type GOPRO_PROTUNE_GAIN int

GOPRO_PROTUNE_GAIN type

const (
	// GOPRO_PROTUNE_GAIN_400 enum. ISO 400
	GOPRO_PROTUNE_GAIN_400 GOPRO_PROTUNE_GAIN = 0
	// GOPRO_PROTUNE_GAIN_800 enum. ISO 800 (Only Hero 4)
	GOPRO_PROTUNE_GAIN_800 GOPRO_PROTUNE_GAIN = 1
	// GOPRO_PROTUNE_GAIN_1600 enum. ISO 1600
	GOPRO_PROTUNE_GAIN_1600 GOPRO_PROTUNE_GAIN = 2
	// GOPRO_PROTUNE_GAIN_3200 enum. ISO 3200 (Only Hero 4)
	GOPRO_PROTUNE_GAIN_3200 GOPRO_PROTUNE_GAIN = 3
	// GOPRO_PROTUNE_GAIN_6400 enum. ISO 6400
	GOPRO_PROTUNE_GAIN_6400 GOPRO_PROTUNE_GAIN = 4
)

func (GOPRO_PROTUNE_GAIN) Bitmask

func (e GOPRO_PROTUNE_GAIN) Bitmask() string

Bitmask return string representetion of intersects GOPRO_PROTUNE_GAIN enums

func (GOPRO_PROTUNE_GAIN) MarshalBinary

func (e GOPRO_PROTUNE_GAIN) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_PROTUNE_GAIN) String

func (e GOPRO_PROTUNE_GAIN) String() string

func (*GOPRO_PROTUNE_GAIN) UnmarshalBinary

func (e *GOPRO_PROTUNE_GAIN) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_PROTUNE_SHARPNESS

type GOPRO_PROTUNE_SHARPNESS int

GOPRO_PROTUNE_SHARPNESS type

const (
	// GOPRO_PROTUNE_SHARPNESS_LOW enum. Low Sharpness
	GOPRO_PROTUNE_SHARPNESS_LOW GOPRO_PROTUNE_SHARPNESS = 0
	// GOPRO_PROTUNE_SHARPNESS_MEDIUM enum. Medium Sharpness
	GOPRO_PROTUNE_SHARPNESS_MEDIUM GOPRO_PROTUNE_SHARPNESS = 1
	// GOPRO_PROTUNE_SHARPNESS_HIGH enum. High Sharpness
	GOPRO_PROTUNE_SHARPNESS_HIGH GOPRO_PROTUNE_SHARPNESS = 2
)

func (GOPRO_PROTUNE_SHARPNESS) Bitmask

func (e GOPRO_PROTUNE_SHARPNESS) Bitmask() string

Bitmask return string representetion of intersects GOPRO_PROTUNE_SHARPNESS enums

func (GOPRO_PROTUNE_SHARPNESS) MarshalBinary

func (e GOPRO_PROTUNE_SHARPNESS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_PROTUNE_SHARPNESS) String

func (e GOPRO_PROTUNE_SHARPNESS) String() string

func (*GOPRO_PROTUNE_SHARPNESS) UnmarshalBinary

func (e *GOPRO_PROTUNE_SHARPNESS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_PROTUNE_WHITE_BALANCE

type GOPRO_PROTUNE_WHITE_BALANCE int

GOPRO_PROTUNE_WHITE_BALANCE type

const (
	// GOPRO_PROTUNE_WHITE_BALANCE_AUTO enum. Auto
	GOPRO_PROTUNE_WHITE_BALANCE_AUTO GOPRO_PROTUNE_WHITE_BALANCE = 0
	// GOPRO_PROTUNE_WHITE_BALANCE_3000K enum. 3000K
	GOPRO_PROTUNE_WHITE_BALANCE_3000K GOPRO_PROTUNE_WHITE_BALANCE = 1
	// GOPRO_PROTUNE_WHITE_BALANCE_5500K enum. 5500K
	GOPRO_PROTUNE_WHITE_BALANCE_5500K GOPRO_PROTUNE_WHITE_BALANCE = 2
	// GOPRO_PROTUNE_WHITE_BALANCE_6500K enum. 6500K
	GOPRO_PROTUNE_WHITE_BALANCE_6500K GOPRO_PROTUNE_WHITE_BALANCE = 3
	// GOPRO_PROTUNE_WHITE_BALANCE_RAW enum. Camera Raw
	GOPRO_PROTUNE_WHITE_BALANCE_RAW GOPRO_PROTUNE_WHITE_BALANCE = 4
)

func (GOPRO_PROTUNE_WHITE_BALANCE) Bitmask

func (e GOPRO_PROTUNE_WHITE_BALANCE) Bitmask() string

Bitmask return string representetion of intersects GOPRO_PROTUNE_WHITE_BALANCE enums

func (GOPRO_PROTUNE_WHITE_BALANCE) MarshalBinary

func (e GOPRO_PROTUNE_WHITE_BALANCE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_PROTUNE_WHITE_BALANCE) String

func (*GOPRO_PROTUNE_WHITE_BALANCE) UnmarshalBinary

func (e *GOPRO_PROTUNE_WHITE_BALANCE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_REQUEST_STATUS

type GOPRO_REQUEST_STATUS int

GOPRO_REQUEST_STATUS type

const (
	// GOPRO_REQUEST_SUCCESS enum. The write message with ID indicated succeeded
	GOPRO_REQUEST_SUCCESS GOPRO_REQUEST_STATUS = 0
	// GOPRO_REQUEST_FAILED enum. The write message with ID indicated failed
	GOPRO_REQUEST_FAILED GOPRO_REQUEST_STATUS = 1
)

func (GOPRO_REQUEST_STATUS) Bitmask

func (e GOPRO_REQUEST_STATUS) Bitmask() string

Bitmask return string representetion of intersects GOPRO_REQUEST_STATUS enums

func (GOPRO_REQUEST_STATUS) MarshalBinary

func (e GOPRO_REQUEST_STATUS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_REQUEST_STATUS) String

func (e GOPRO_REQUEST_STATUS) String() string

func (*GOPRO_REQUEST_STATUS) UnmarshalBinary

func (e *GOPRO_REQUEST_STATUS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_RESOLUTION

type GOPRO_RESOLUTION int

GOPRO_RESOLUTION type

const (
	// GOPRO_RESOLUTION_480p enum. 848 x 480 (480p)
	GOPRO_RESOLUTION_480p GOPRO_RESOLUTION = 0
	// GOPRO_RESOLUTION_720p enum. 1280 x 720 (720p)
	GOPRO_RESOLUTION_720p GOPRO_RESOLUTION = 1
	// GOPRO_RESOLUTION_960p enum. 1280 x 960 (960p)
	GOPRO_RESOLUTION_960p GOPRO_RESOLUTION = 2
	// GOPRO_RESOLUTION_1080p enum. 1920 x 1080 (1080p)
	GOPRO_RESOLUTION_1080p GOPRO_RESOLUTION = 3
	// GOPRO_RESOLUTION_1440p enum. 1920 x 1440 (1440p)
	GOPRO_RESOLUTION_1440p GOPRO_RESOLUTION = 4
	// GOPRO_RESOLUTION_2_7k_17_9 enum. 2704 x 1440 (2.7k-17:9)
	GOPRO_RESOLUTION_2_7k_17_9 GOPRO_RESOLUTION = 5
	// GOPRO_RESOLUTION_2_7k_16_9 enum. 2704 x 1524 (2.7k-16:9)
	GOPRO_RESOLUTION_2_7k_16_9 GOPRO_RESOLUTION = 6
	// GOPRO_RESOLUTION_2_7k_4_3 enum. 2704 x 2028 (2.7k-4:3)
	GOPRO_RESOLUTION_2_7k_4_3 GOPRO_RESOLUTION = 7
	// GOPRO_RESOLUTION_4k_16_9 enum. 3840 x 2160 (4k-16:9)
	GOPRO_RESOLUTION_4k_16_9 GOPRO_RESOLUTION = 8
	// GOPRO_RESOLUTION_4k_17_9 enum. 4096 x 2160 (4k-17:9)
	GOPRO_RESOLUTION_4k_17_9 GOPRO_RESOLUTION = 9
	// GOPRO_RESOLUTION_720p_SUPERVIEW enum. 1280 x 720 (720p-SuperView)
	GOPRO_RESOLUTION_720p_SUPERVIEW GOPRO_RESOLUTION = 10
	// GOPRO_RESOLUTION_1080p_SUPERVIEW enum. 1920 x 1080 (1080p-SuperView)
	GOPRO_RESOLUTION_1080p_SUPERVIEW GOPRO_RESOLUTION = 11
	// GOPRO_RESOLUTION_2_7k_SUPERVIEW enum. 2704 x 1520 (2.7k-SuperView)
	GOPRO_RESOLUTION_2_7k_SUPERVIEW GOPRO_RESOLUTION = 12
	// GOPRO_RESOLUTION_4k_SUPERVIEW enum. 3840 x 2160 (4k-SuperView)
	GOPRO_RESOLUTION_4k_SUPERVIEW GOPRO_RESOLUTION = 13
)

func (GOPRO_RESOLUTION) Bitmask

func (e GOPRO_RESOLUTION) Bitmask() string

Bitmask return string representetion of intersects GOPRO_RESOLUTION enums

func (GOPRO_RESOLUTION) MarshalBinary

func (e GOPRO_RESOLUTION) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_RESOLUTION) String

func (e GOPRO_RESOLUTION) String() string

func (*GOPRO_RESOLUTION) UnmarshalBinary

func (e *GOPRO_RESOLUTION) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GOPRO_VIDEO_SETTINGS_FLAGS

type GOPRO_VIDEO_SETTINGS_FLAGS int

GOPRO_VIDEO_SETTINGS_FLAGS type

const (
	// GOPRO_VIDEO_SETTINGS_TV_MODE enum. 0=NTSC, 1=PAL
	GOPRO_VIDEO_SETTINGS_TV_MODE GOPRO_VIDEO_SETTINGS_FLAGS = 1
)

func (GOPRO_VIDEO_SETTINGS_FLAGS) Bitmask

func (e GOPRO_VIDEO_SETTINGS_FLAGS) Bitmask() string

Bitmask return string representetion of intersects GOPRO_VIDEO_SETTINGS_FLAGS enums

func (GOPRO_VIDEO_SETTINGS_FLAGS) MarshalBinary

func (e GOPRO_VIDEO_SETTINGS_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GOPRO_VIDEO_SETTINGS_FLAGS) String

func (*GOPRO_VIDEO_SETTINGS_FLAGS) UnmarshalBinary

func (e *GOPRO_VIDEO_SETTINGS_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GPS_FIX_TYPE

type GPS_FIX_TYPE int

GPS_FIX_TYPE type. Type of GPS fix

const (
	// GPS_FIX_TYPE_NO_GPS enum. No GPS connected
	GPS_FIX_TYPE_NO_GPS GPS_FIX_TYPE = 0
	// GPS_FIX_TYPE_NO_FIX enum. No position information, GPS is connected
	GPS_FIX_TYPE_NO_FIX GPS_FIX_TYPE = 1
	// GPS_FIX_TYPE_2D_FIX enum. 2D position
	GPS_FIX_TYPE_2D_FIX GPS_FIX_TYPE = 2
	// GPS_FIX_TYPE_3D_FIX enum. 3D position
	GPS_FIX_TYPE_3D_FIX GPS_FIX_TYPE = 3
	// GPS_FIX_TYPE_DGPS enum. DGPS/SBAS aided 3D position
	GPS_FIX_TYPE_DGPS GPS_FIX_TYPE = 4
	// GPS_FIX_TYPE_RTK_FLOAT enum. RTK float, 3D position
	GPS_FIX_TYPE_RTK_FLOAT GPS_FIX_TYPE = 5
	// GPS_FIX_TYPE_RTK_FIXED enum. RTK Fixed, 3D position
	GPS_FIX_TYPE_RTK_FIXED GPS_FIX_TYPE = 6
	// GPS_FIX_TYPE_STATIC enum. Static fixed, typically used for base stations
	GPS_FIX_TYPE_STATIC GPS_FIX_TYPE = 7
	// GPS_FIX_TYPE_PPP enum. PPP, 3D position
	GPS_FIX_TYPE_PPP GPS_FIX_TYPE = 8
)

func (GPS_FIX_TYPE) Bitmask

func (e GPS_FIX_TYPE) Bitmask() string

Bitmask return string representetion of intersects GPS_FIX_TYPE enums

func (GPS_FIX_TYPE) MarshalBinary

func (e GPS_FIX_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GPS_FIX_TYPE) String

func (e GPS_FIX_TYPE) String() string

func (*GPS_FIX_TYPE) UnmarshalBinary

func (e *GPS_FIX_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GPS_INPUT_IGNORE_FLAGS

type GPS_INPUT_IGNORE_FLAGS int

GPS_INPUT_IGNORE_FLAGS type

const (
	// GPS_INPUT_IGNORE_FLAG_ALT enum. ignore altitude field
	GPS_INPUT_IGNORE_FLAG_ALT GPS_INPUT_IGNORE_FLAGS = 1
	// GPS_INPUT_IGNORE_FLAG_HDOP enum. ignore hdop field
	GPS_INPUT_IGNORE_FLAG_HDOP GPS_INPUT_IGNORE_FLAGS = 2
	// GPS_INPUT_IGNORE_FLAG_VDOP enum. ignore vdop field
	GPS_INPUT_IGNORE_FLAG_VDOP GPS_INPUT_IGNORE_FLAGS = 4
	// GPS_INPUT_IGNORE_FLAG_VEL_HORIZ enum. ignore horizontal velocity field (vn and ve)
	GPS_INPUT_IGNORE_FLAG_VEL_HORIZ GPS_INPUT_IGNORE_FLAGS = 8
	// GPS_INPUT_IGNORE_FLAG_VEL_VERT enum. ignore vertical velocity field (vd)
	GPS_INPUT_IGNORE_FLAG_VEL_VERT GPS_INPUT_IGNORE_FLAGS = 16
	// GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY enum. ignore speed accuracy field
	GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY GPS_INPUT_IGNORE_FLAGS = 32
	// GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY enum. ignore horizontal accuracy field
	GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY GPS_INPUT_IGNORE_FLAGS = 64
	// GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY enum. ignore vertical accuracy field
	GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY GPS_INPUT_IGNORE_FLAGS = 128
)

func (GPS_INPUT_IGNORE_FLAGS) Bitmask

func (e GPS_INPUT_IGNORE_FLAGS) Bitmask() string

Bitmask return string representetion of intersects GPS_INPUT_IGNORE_FLAGS enums

func (GPS_INPUT_IGNORE_FLAGS) MarshalBinary

func (e GPS_INPUT_IGNORE_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GPS_INPUT_IGNORE_FLAGS) String

func (e GPS_INPUT_IGNORE_FLAGS) String() string

func (*GPS_INPUT_IGNORE_FLAGS) UnmarshalBinary

func (e *GPS_INPUT_IGNORE_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GRIPPER_ACTIONS

type GRIPPER_ACTIONS int

GRIPPER_ACTIONS type. Gripper actions.

const (
	// GRIPPER_ACTION_RELEASE enum. Gripper release cargo
	GRIPPER_ACTION_RELEASE GRIPPER_ACTIONS = 0
	// GRIPPER_ACTION_GRAB enum. Gripper grab onto cargo
	GRIPPER_ACTION_GRAB GRIPPER_ACTIONS = 1
)

func (GRIPPER_ACTIONS) Bitmask

func (e GRIPPER_ACTIONS) Bitmask() string

Bitmask return string representetion of intersects GRIPPER_ACTIONS enums

func (GRIPPER_ACTIONS) MarshalBinary

func (e GRIPPER_ACTIONS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (GRIPPER_ACTIONS) String

func (e GRIPPER_ACTIONS) String() string

func (*GRIPPER_ACTIONS) UnmarshalBinary

func (e *GRIPPER_ACTIONS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type GimbalControl

type GimbalControl struct {
	DemandedRateX   float32 `json:"DemandedRateX" `   // [ rad/s ] Demanded angular rate X.
	DemandedRateY   float32 `json:"DemandedRateY" `   // [ rad/s ] Demanded angular rate Y.
	DemandedRateZ   float32 `json:"DemandedRateZ" `   // [ rad/s ] Demanded angular rate Z.
	TargetSystem    uint8   `json:"TargetSystem" `    // System ID.
	TargetComponent uint8   `json:"TargetComponent" ` // Component ID.
}

GimbalControl struct (generated typeinfo) Control message for rate gimbal.

func (*GimbalControl) Dict

func (m *GimbalControl) Dict() map[string]interface{}

ToMap (generated function)

func (*GimbalControl) Marshal

func (m *GimbalControl) Marshal() ([]byte, error)

Marshal (generated function)

func (GimbalControl) MarshalEasyJSON added in v1.5.0

func (v GimbalControl) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GimbalControl) MarshalJSON added in v1.5.0

func (v GimbalControl) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GimbalControl) MsgID

func (m *GimbalControl) MsgID() message.MessageID

MsgID (generated function)

func (*GimbalControl) String

func (m *GimbalControl) String() string

String (generated function)

func (*GimbalControl) Unmarshal

func (m *GimbalControl) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GimbalControl) UnmarshalEasyJSON added in v1.5.0

func (v *GimbalControl) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GimbalControl) UnmarshalJSON added in v1.5.0

func (v *GimbalControl) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GimbalReport

type GimbalReport struct {
	DeltaTime       float32 `json:"DeltaTime" `       // [ s ] Time since last update.
	DeltaAngleX     float32 `json:"DeltaAngleX" `     // [ rad ] Delta angle X.
	DeltaAngleY     float32 `json:"DeltaAngleY" `     // [ rad ] Delta angle Y.
	DeltaAngleZ     float32 `json:"DeltaAngleZ" `     // [ rad ] Delta angle X.
	DeltaVelocityX  float32 `json:"DeltaVelocityX" `  // [ m/s ] Delta velocity X.
	DeltaVelocityY  float32 `json:"DeltaVelocityY" `  // [ m/s ] Delta velocity Y.
	DeltaVelocityZ  float32 `json:"DeltaVelocityZ" `  // [ m/s ] Delta velocity Z.
	JointRoll       float32 `json:"JointRoll" `       // [ rad ] Joint ROLL.
	JointEl         float32 `json:"JointEl" `         // [ rad ] Joint EL.
	JointAz         float32 `json:"JointAz" `         // [ rad ] Joint AZ.
	TargetSystem    uint8   `json:"TargetSystem" `    // System ID.
	TargetComponent uint8   `json:"TargetComponent" ` // Component ID.
}

GimbalReport struct (generated typeinfo) 3 axis gimbal measurements.

func (*GimbalReport) Dict

func (m *GimbalReport) Dict() map[string]interface{}

ToMap (generated function)

func (*GimbalReport) Marshal

func (m *GimbalReport) Marshal() ([]byte, error)

Marshal (generated function)

func (GimbalReport) MarshalEasyJSON added in v1.5.0

func (v GimbalReport) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GimbalReport) MarshalJSON added in v1.5.0

func (v GimbalReport) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GimbalReport) MsgID

func (m *GimbalReport) MsgID() message.MessageID

MsgID (generated function)

func (*GimbalReport) String

func (m *GimbalReport) String() string

String (generated function)

func (*GimbalReport) Unmarshal

func (m *GimbalReport) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GimbalReport) UnmarshalEasyJSON added in v1.5.0

func (v *GimbalReport) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GimbalReport) UnmarshalJSON added in v1.5.0

func (v *GimbalReport) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GimbalTorqueCmdReport

type GimbalTorqueCmdReport struct {
	RlTorqueCmd     int16 `json:"RlTorqueCmd" `     // Roll Torque Command.
	ElTorqueCmd     int16 `json:"ElTorqueCmd" `     // Elevation Torque Command.
	AzTorqueCmd     int16 `json:"AzTorqueCmd" `     // Azimuth Torque Command.
	TargetSystem    uint8 `json:"TargetSystem" `    // System ID.
	TargetComponent uint8 `json:"TargetComponent" ` // Component ID.
}

GimbalTorqueCmdReport struct (generated typeinfo) 100 Hz gimbal torque command telemetry.

func (*GimbalTorqueCmdReport) Dict

func (m *GimbalTorqueCmdReport) Dict() map[string]interface{}

ToMap (generated function)

func (*GimbalTorqueCmdReport) Marshal

func (m *GimbalTorqueCmdReport) Marshal() ([]byte, error)

Marshal (generated function)

func (GimbalTorqueCmdReport) MarshalEasyJSON added in v1.5.0

func (v GimbalTorqueCmdReport) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GimbalTorqueCmdReport) MarshalJSON added in v1.5.0

func (v GimbalTorqueCmdReport) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GimbalTorqueCmdReport) MsgID

MsgID (generated function)

func (*GimbalTorqueCmdReport) String

func (m *GimbalTorqueCmdReport) String() string

String (generated function)

func (*GimbalTorqueCmdReport) Unmarshal

func (m *GimbalTorqueCmdReport) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GimbalTorqueCmdReport) UnmarshalEasyJSON added in v1.5.0

func (v *GimbalTorqueCmdReport) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GimbalTorqueCmdReport) UnmarshalJSON added in v1.5.0

func (v *GimbalTorqueCmdReport) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GlobalPositionInt

type GlobalPositionInt struct {
	TimeBootMs  uint32 `json:"TimeBootMs" `  // [ ms ] Timestamp (time since system boot).
	Lat         int32  `json:"Lat" `         // [ degE7 ] Latitude, expressed
	Lon         int32  `json:"Lon" `         // [ degE7 ] Longitude, expressed
	Alt         int32  `json:"Alt" `         // [ mm ] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.
	RelativeAlt int32  `json:"RelativeAlt" ` // [ mm ] Altitude above ground
	Vx          int16  `json:"Vx" `          // [ cm/s ] Ground X Speed (Latitude, positive north)
	Vy          int16  `json:"Vy" `          // [ cm/s ] Ground Y Speed (Longitude, positive east)
	Vz          int16  `json:"Vz" `          // [ cm/s ] Ground Z Speed (Altitude, positive down)
	Hdg         uint16 `json:"Hdg" `         // [ cdeg ] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
}

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

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

func (*GlobalPositionInt) Dict

func (m *GlobalPositionInt) Dict() map[string]interface{}

ToMap (generated function)

func (*GlobalPositionInt) Marshal

func (m *GlobalPositionInt) Marshal() ([]byte, error)

Marshal (generated function)

func (GlobalPositionInt) MarshalEasyJSON added in v1.5.0

func (v GlobalPositionInt) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GlobalPositionInt) MarshalJSON added in v1.5.0

func (v GlobalPositionInt) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GlobalPositionInt) MsgID

func (m *GlobalPositionInt) MsgID() message.MessageID

MsgID (generated function)

func (*GlobalPositionInt) String

func (m *GlobalPositionInt) String() string

String (generated function)

func (*GlobalPositionInt) Unmarshal

func (m *GlobalPositionInt) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GlobalPositionInt) UnmarshalEasyJSON added in v1.5.0

func (v *GlobalPositionInt) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GlobalPositionInt) UnmarshalJSON added in v1.5.0

func (v *GlobalPositionInt) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GlobalPositionIntCov

type GlobalPositionIntCov struct {
	TimeUsec      uint64             `json:"TimeUsec" `            // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Lat           int32              `json:"Lat" `                 // [ degE7 ] Latitude
	Lon           int32              `json:"Lon" `                 // [ degE7 ] Longitude
	Alt           int32              `json:"Alt" `                 // [ mm ] Altitude in meters above MSL
	RelativeAlt   int32              `json:"RelativeAlt" `         // [ mm ] Altitude above ground
	Vx            float32            `json:"Vx" `                  // [ m/s ] Ground X Speed (Latitude)
	Vy            float32            `json:"Vy" `                  // [ m/s ] Ground Y Speed (Longitude)
	Vz            float32            `json:"Vz" `                  // [ m/s ] Ground Z Speed (Altitude)
	Covariance    []float32          `json:"Covariance" len:"36" ` // Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
	EstimatorType MAV_ESTIMATOR_TYPE `json:"EstimatorType" `       // Class id of the estimator this estimate originated from.
}

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

func (*GlobalPositionIntCov) Dict

func (m *GlobalPositionIntCov) Dict() map[string]interface{}

ToMap (generated function)

func (*GlobalPositionIntCov) Marshal

func (m *GlobalPositionIntCov) Marshal() ([]byte, error)

Marshal (generated function)

func (GlobalPositionIntCov) MarshalEasyJSON added in v1.5.0

func (v GlobalPositionIntCov) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GlobalPositionIntCov) MarshalJSON added in v1.5.0

func (v GlobalPositionIntCov) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GlobalPositionIntCov) MsgID

MsgID (generated function)

func (*GlobalPositionIntCov) String

func (m *GlobalPositionIntCov) String() string

String (generated function)

func (*GlobalPositionIntCov) Unmarshal

func (m *GlobalPositionIntCov) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GlobalPositionIntCov) UnmarshalEasyJSON added in v1.5.0

func (v *GlobalPositionIntCov) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GlobalPositionIntCov) UnmarshalJSON added in v1.5.0

func (v *GlobalPositionIntCov) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GlobalVisionPositionEstimate

type GlobalVisionPositionEstimate struct {
	Usec  uint64  `json:"Usec" `  // [ us ] Timestamp (UNIX time or since system boot)
	X     float32 `json:"X" `     // [ m ] Global X position
	Y     float32 `json:"Y" `     // [ m ] Global Y position
	Z     float32 `json:"Z" `     // [ m ] Global Z position
	Roll  float32 `json:"Roll" `  // [ rad ] Roll angle
	Pitch float32 `json:"Pitch" ` // [ rad ] Pitch angle
	Yaw   float32 `json:"Yaw" `   // [ rad ] Yaw angle
}

GlobalVisionPositionEstimate struct (generated typeinfo) Global position/attitude estimate from a vision source.

func (*GlobalVisionPositionEstimate) Dict

func (m *GlobalVisionPositionEstimate) Dict() map[string]interface{}

ToMap (generated function)

func (*GlobalVisionPositionEstimate) Marshal

func (m *GlobalVisionPositionEstimate) Marshal() ([]byte, error)

Marshal (generated function)

func (GlobalVisionPositionEstimate) MarshalEasyJSON added in v1.5.0

func (v GlobalVisionPositionEstimate) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GlobalVisionPositionEstimate) MarshalJSON added in v1.5.0

func (v GlobalVisionPositionEstimate) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GlobalVisionPositionEstimate) MsgID

MsgID (generated function)

func (*GlobalVisionPositionEstimate) String

String (generated function)

func (*GlobalVisionPositionEstimate) Unmarshal

func (m *GlobalVisionPositionEstimate) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GlobalVisionPositionEstimate) UnmarshalEasyJSON added in v1.5.0

func (v *GlobalVisionPositionEstimate) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GlobalVisionPositionEstimate) UnmarshalJSON added in v1.5.0

func (v *GlobalVisionPositionEstimate) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GoproGetRequest

type GoproGetRequest struct {
	TargetSystem    uint8         `json:"TargetSystem" `    // System ID.
	TargetComponent uint8         `json:"TargetComponent" ` // Component ID.
	CmdID           GOPRO_COMMAND `json:"CmdID" `           // Command ID.
}

GoproGetRequest struct (generated typeinfo) Request a GOPRO_COMMAND response from the GoPro.

func (*GoproGetRequest) Dict

func (m *GoproGetRequest) Dict() map[string]interface{}

ToMap (generated function)

func (*GoproGetRequest) Marshal

func (m *GoproGetRequest) Marshal() ([]byte, error)

Marshal (generated function)

func (GoproGetRequest) MarshalEasyJSON added in v1.5.0

func (v GoproGetRequest) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GoproGetRequest) MarshalJSON added in v1.5.0

func (v GoproGetRequest) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GoproGetRequest) MsgID

func (m *GoproGetRequest) MsgID() message.MessageID

MsgID (generated function)

func (*GoproGetRequest) String

func (m *GoproGetRequest) String() string

String (generated function)

func (*GoproGetRequest) Unmarshal

func (m *GoproGetRequest) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GoproGetRequest) UnmarshalEasyJSON added in v1.5.0

func (v *GoproGetRequest) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GoproGetRequest) UnmarshalJSON added in v1.5.0

func (v *GoproGetRequest) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GoproGetResponse

type GoproGetResponse struct {
	CmdID  GOPRO_COMMAND        `json:"CmdID" `         // Command ID.
	Status GOPRO_REQUEST_STATUS `json:"Status" `        // Status.
	Value  []uint8              `json:"Value" len:"4" ` // Value.
}

GoproGetResponse struct (generated typeinfo) Response from a GOPRO_COMMAND get request.

func (*GoproGetResponse) Dict

func (m *GoproGetResponse) Dict() map[string]interface{}

ToMap (generated function)

func (*GoproGetResponse) Marshal

func (m *GoproGetResponse) Marshal() ([]byte, error)

Marshal (generated function)

func (GoproGetResponse) MarshalEasyJSON added in v1.5.0

func (v GoproGetResponse) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GoproGetResponse) MarshalJSON added in v1.5.0

func (v GoproGetResponse) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GoproGetResponse) MsgID

func (m *GoproGetResponse) MsgID() message.MessageID

MsgID (generated function)

func (*GoproGetResponse) String

func (m *GoproGetResponse) String() string

String (generated function)

func (*GoproGetResponse) Unmarshal

func (m *GoproGetResponse) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GoproGetResponse) UnmarshalEasyJSON added in v1.5.0

func (v *GoproGetResponse) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GoproGetResponse) UnmarshalJSON added in v1.5.0

func (v *GoproGetResponse) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GoproHeartbeat

type GoproHeartbeat struct {
	Status      GOPRO_HEARTBEAT_STATUS `json:"Status" `      // Status.
	CaptureMode GOPRO_CAPTURE_MODE     `json:"CaptureMode" ` // Current capture mode.
	Flags       GOPRO_HEARTBEAT_FLAGS  `json:"Flags" `       // Additional status bits.
}

GoproHeartbeat struct (generated typeinfo) Heartbeat from a HeroBus attached GoPro.

func (*GoproHeartbeat) Dict

func (m *GoproHeartbeat) Dict() map[string]interface{}

ToMap (generated function)

func (*GoproHeartbeat) Marshal

func (m *GoproHeartbeat) Marshal() ([]byte, error)

Marshal (generated function)

func (GoproHeartbeat) MarshalEasyJSON added in v1.5.0

func (v GoproHeartbeat) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GoproHeartbeat) MarshalJSON added in v1.5.0

func (v GoproHeartbeat) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GoproHeartbeat) MsgID

func (m *GoproHeartbeat) MsgID() message.MessageID

MsgID (generated function)

func (*GoproHeartbeat) String

func (m *GoproHeartbeat) String() string

String (generated function)

func (*GoproHeartbeat) Unmarshal

func (m *GoproHeartbeat) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GoproHeartbeat) UnmarshalEasyJSON added in v1.5.0

func (v *GoproHeartbeat) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GoproHeartbeat) UnmarshalJSON added in v1.5.0

func (v *GoproHeartbeat) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GoproSetRequest

type GoproSetRequest struct {
	TargetSystem    uint8         `json:"TargetSystem" `    // System ID.
	TargetComponent uint8         `json:"TargetComponent" ` // Component ID.
	CmdID           GOPRO_COMMAND `json:"CmdID" `           // Command ID.
	Value           []uint8       `json:"Value" len:"4" `   // Value.
}

GoproSetRequest struct (generated typeinfo) Request to set a GOPRO_COMMAND with a desired.

func (*GoproSetRequest) Dict

func (m *GoproSetRequest) Dict() map[string]interface{}

ToMap (generated function)

func (*GoproSetRequest) Marshal

func (m *GoproSetRequest) Marshal() ([]byte, error)

Marshal (generated function)

func (GoproSetRequest) MarshalEasyJSON added in v1.5.0

func (v GoproSetRequest) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GoproSetRequest) MarshalJSON added in v1.5.0

func (v GoproSetRequest) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GoproSetRequest) MsgID

func (m *GoproSetRequest) MsgID() message.MessageID

MsgID (generated function)

func (*GoproSetRequest) String

func (m *GoproSetRequest) String() string

String (generated function)

func (*GoproSetRequest) Unmarshal

func (m *GoproSetRequest) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GoproSetRequest) UnmarshalEasyJSON added in v1.5.0

func (v *GoproSetRequest) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GoproSetRequest) UnmarshalJSON added in v1.5.0

func (v *GoproSetRequest) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GoproSetResponse

type GoproSetResponse struct {
	CmdID  GOPRO_COMMAND        `json:"CmdID" `  // Command ID.
	Status GOPRO_REQUEST_STATUS `json:"Status" ` // Status.
}

GoproSetResponse struct (generated typeinfo) Response from a GOPRO_COMMAND set request.

func (*GoproSetResponse) Dict

func (m *GoproSetResponse) Dict() map[string]interface{}

ToMap (generated function)

func (*GoproSetResponse) Marshal

func (m *GoproSetResponse) Marshal() ([]byte, error)

Marshal (generated function)

func (GoproSetResponse) MarshalEasyJSON added in v1.5.0

func (v GoproSetResponse) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GoproSetResponse) MarshalJSON added in v1.5.0

func (v GoproSetResponse) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GoproSetResponse) MsgID

func (m *GoproSetResponse) MsgID() message.MessageID

MsgID (generated function)

func (*GoproSetResponse) String

func (m *GoproSetResponse) String() string

String (generated function)

func (*GoproSetResponse) Unmarshal

func (m *GoproSetResponse) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GoproSetResponse) UnmarshalEasyJSON added in v1.5.0

func (v *GoproSetResponse) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GoproSetResponse) UnmarshalJSON added in v1.5.0

func (v *GoproSetResponse) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Gps2Raw

type Gps2Raw struct {
	TimeUsec          uint64       `json:"TimeUsec" `          // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Lat               int32        `json:"Lat" `               // [ degE7 ] Latitude (WGS84)
	Lon               int32        `json:"Lon" `               // [ degE7 ] Longitude (WGS84)
	Alt               int32        `json:"Alt" `               // [ mm ] Altitude (MSL). Positive for up.
	DgpsAge           uint32       `json:"DgpsAge" `           // [ ms ] Age of DGPS info
	Eph               uint16       `json:"Eph" `               // GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
	Epv               uint16       `json:"Epv" `               // GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
	Vel               uint16       `json:"Vel" `               // [ cm/s ] GPS ground speed. If unknown, set to: UINT16_MAX
	Cog               uint16       `json:"Cog" `               // [ cdeg ] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
	FixType           GPS_FIX_TYPE `json:"FixType" `           // GPS fix type.
	SatellitesVisible uint8        `json:"SatellitesVisible" ` // Number of satellites visible. If unknown, set to 255
	DgpsNumch         uint8        `json:"DgpsNumch" `         // Number of DGPS satellites
}

Gps2Raw struct (generated typeinfo) Second GPS data.

func (*Gps2Raw) Dict

func (m *Gps2Raw) Dict() map[string]interface{}

ToMap (generated function)

func (*Gps2Raw) Marshal

func (m *Gps2Raw) Marshal() ([]byte, error)

Marshal (generated function)

func (Gps2Raw) MarshalEasyJSON added in v1.5.0

func (v Gps2Raw) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Gps2Raw) MarshalJSON added in v1.5.0

func (v Gps2Raw) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Gps2Raw) MsgID

func (m *Gps2Raw) MsgID() message.MessageID

MsgID (generated function)

func (*Gps2Raw) String

func (m *Gps2Raw) String() string

String (generated function)

func (*Gps2Raw) Unmarshal

func (m *Gps2Raw) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Gps2Raw) UnmarshalEasyJSON added in v1.5.0

func (v *Gps2Raw) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Gps2Raw) UnmarshalJSON added in v1.5.0

func (v *Gps2Raw) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Gps2Rtk

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

Gps2Rtk struct (generated typeinfo) RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting

func (*Gps2Rtk) Dict

func (m *Gps2Rtk) Dict() map[string]interface{}

ToMap (generated function)

func (*Gps2Rtk) Marshal

func (m *Gps2Rtk) Marshal() ([]byte, error)

Marshal (generated function)

func (Gps2Rtk) MarshalEasyJSON added in v1.5.0

func (v Gps2Rtk) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Gps2Rtk) MarshalJSON added in v1.5.0

func (v Gps2Rtk) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Gps2Rtk) MsgID

func (m *Gps2Rtk) MsgID() message.MessageID

MsgID (generated function)

func (*Gps2Rtk) String

func (m *Gps2Rtk) String() string

String (generated function)

func (*Gps2Rtk) Unmarshal

func (m *Gps2Rtk) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Gps2Rtk) UnmarshalEasyJSON added in v1.5.0

func (v *Gps2Rtk) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Gps2Rtk) UnmarshalJSON added in v1.5.0

func (v *Gps2Rtk) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GpsGlobalOrigin

type GpsGlobalOrigin struct {
	Latitude  int32 `json:"Latitude" `  // [ degE7 ] Latitude (WGS84)
	Longitude int32 `json:"Longitude" ` // [ degE7 ] Longitude (WGS84)
	Altitude  int32 `json:"Altitude" `  // [ mm ] Altitude (MSL). Positive for up.
}

GpsGlobalOrigin struct (generated typeinfo) Publishes the GPS co-ordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message.

func (*GpsGlobalOrigin) Dict

func (m *GpsGlobalOrigin) Dict() map[string]interface{}

ToMap (generated function)

func (*GpsGlobalOrigin) Marshal

func (m *GpsGlobalOrigin) Marshal() ([]byte, error)

Marshal (generated function)

func (GpsGlobalOrigin) MarshalEasyJSON added in v1.5.0

func (v GpsGlobalOrigin) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GpsGlobalOrigin) MarshalJSON added in v1.5.0

func (v GpsGlobalOrigin) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GpsGlobalOrigin) MsgID

func (m *GpsGlobalOrigin) MsgID() message.MessageID

MsgID (generated function)

func (*GpsGlobalOrigin) String

func (m *GpsGlobalOrigin) String() string

String (generated function)

func (*GpsGlobalOrigin) Unmarshal

func (m *GpsGlobalOrigin) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GpsGlobalOrigin) UnmarshalEasyJSON added in v1.5.0

func (v *GpsGlobalOrigin) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GpsGlobalOrigin) UnmarshalJSON added in v1.5.0

func (v *GpsGlobalOrigin) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GpsInjectData

type GpsInjectData struct {
	TargetSystem    uint8   `json:"TargetSystem" `    // System ID
	TargetComponent uint8   `json:"TargetComponent" ` // Component ID
	Len             uint8   `json:"Len" `             // [ bytes ] Data length
	Data            []uint8 `json:"Data" len:"110" `  // Raw data (110 is enough for 12 satellites of RTCMv2)
}

GpsInjectData struct (generated typeinfo) Data for injecting into the onboard GPS (used for DGPS)

func (*GpsInjectData) Dict

func (m *GpsInjectData) Dict() map[string]interface{}

ToMap (generated function)

func (*GpsInjectData) Marshal

func (m *GpsInjectData) Marshal() ([]byte, error)

Marshal (generated function)

func (GpsInjectData) MarshalEasyJSON added in v1.5.0

func (v GpsInjectData) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GpsInjectData) MarshalJSON added in v1.5.0

func (v GpsInjectData) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GpsInjectData) MsgID

func (m *GpsInjectData) MsgID() message.MessageID

MsgID (generated function)

func (*GpsInjectData) String

func (m *GpsInjectData) String() string

String (generated function)

func (*GpsInjectData) Unmarshal

func (m *GpsInjectData) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GpsInjectData) UnmarshalEasyJSON added in v1.5.0

func (v *GpsInjectData) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GpsInjectData) UnmarshalJSON added in v1.5.0

func (v *GpsInjectData) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GpsInput

type GpsInput struct {
	TimeUsec          uint64                 `json:"TimeUsec" `          // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	TimeWeekMs        uint32                 `json:"TimeWeekMs" `        // [ ms ] GPS time (from start of GPS week)
	Lat               int32                  `json:"Lat" `               // [ degE7 ] Latitude (WGS84)
	Lon               int32                  `json:"Lon" `               // [ degE7 ] Longitude (WGS84)
	Alt               float32                `json:"Alt" `               // [ m ] Altitude (MSL). Positive for up.
	Hdop              float32                `json:"Hdop" `              // GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
	Vdop              float32                `json:"Vdop" `              // GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
	Vn                float32                `json:"Vn" `                // [ m/s ] GPS velocity in north direction in earth-fixed NED frame
	Ve                float32                `json:"Ve" `                // [ m/s ] GPS velocity in east direction in earth-fixed NED frame
	Vd                float32                `json:"Vd" `                // [ m/s ] GPS velocity in down direction in earth-fixed NED frame
	SpeedAccuracy     float32                `json:"SpeedAccuracy" `     // [ m/s ] GPS speed accuracy
	HorizAccuracy     float32                `json:"HorizAccuracy" `     // [ m ] GPS horizontal accuracy
	VertAccuracy      float32                `json:"VertAccuracy" `      // [ m ] GPS vertical accuracy
	IgnoreFlags       GPS_INPUT_IGNORE_FLAGS `json:"IgnoreFlags" `       // Bitmap indicating which GPS input flags fields to ignore.  All other fields must be provided.
	TimeWeek          uint16                 `json:"TimeWeek" `          // GPS week number
	GpsID             uint8                  `json:"GpsID" `             // ID of the GPS for multiple GPS inputs
	FixType           uint8                  `json:"FixType" `           // 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
	SatellitesVisible uint8                  `json:"SatellitesVisible" ` // Number of satellites visible.
}

GpsInput struct (generated typeinfo) GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the system.

func (*GpsInput) Dict

func (m *GpsInput) Dict() map[string]interface{}

ToMap (generated function)

func (*GpsInput) Marshal

func (m *GpsInput) Marshal() ([]byte, error)

Marshal (generated function)

func (GpsInput) MarshalEasyJSON added in v1.5.0

func (v GpsInput) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GpsInput) MarshalJSON added in v1.5.0

func (v GpsInput) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GpsInput) MsgID

func (m *GpsInput) MsgID() message.MessageID

MsgID (generated function)

func (*GpsInput) String

func (m *GpsInput) String() string

String (generated function)

func (*GpsInput) Unmarshal

func (m *GpsInput) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GpsInput) UnmarshalEasyJSON added in v1.5.0

func (v *GpsInput) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GpsInput) UnmarshalJSON added in v1.5.0

func (v *GpsInput) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GpsRawInt

type GpsRawInt struct {
	TimeUsec          uint64       `json:"TimeUsec" `          // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Lat               int32        `json:"Lat" `               // [ degE7 ] Latitude (WGS84, EGM96 ellipsoid)
	Lon               int32        `json:"Lon" `               // [ degE7 ] Longitude (WGS84, EGM96 ellipsoid)
	Alt               int32        `json:"Alt" `               // [ mm ] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
	Eph               uint16       `json:"Eph" `               // GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
	Epv               uint16       `json:"Epv" `               // GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
	Vel               uint16       `json:"Vel" `               // [ cm/s ] GPS ground speed. If unknown, set to: UINT16_MAX
	Cog               uint16       `json:"Cog" `               // [ cdeg ] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
	FixType           GPS_FIX_TYPE `json:"FixType" `           // GPS fix type.
	SatellitesVisible uint8        `json:"SatellitesVisible" ` // Number of satellites visible. If unknown, set to 255
}

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

NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate.

func (*GpsRawInt) Dict

func (m *GpsRawInt) Dict() map[string]interface{}

ToMap (generated function)

func (*GpsRawInt) Marshal

func (m *GpsRawInt) Marshal() ([]byte, error)

Marshal (generated function)

func (GpsRawInt) MarshalEasyJSON added in v1.5.0

func (v GpsRawInt) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GpsRawInt) MarshalJSON added in v1.5.0

func (v GpsRawInt) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GpsRawInt) MsgID

func (m *GpsRawInt) MsgID() message.MessageID

MsgID (generated function)

func (*GpsRawInt) String

func (m *GpsRawInt) String() string

String (generated function)

func (*GpsRawInt) Unmarshal

func (m *GpsRawInt) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GpsRawInt) UnmarshalEasyJSON added in v1.5.0

func (v *GpsRawInt) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GpsRawInt) UnmarshalJSON added in v1.5.0

func (v *GpsRawInt) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GpsRtcmData

type GpsRtcmData struct {
	Flags uint8   `json:"Flags" `          // LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.
	Len   uint8   `json:"Len" `            // [ bytes ] data length
	Data  []uint8 `json:"Data" len:"180" ` // RTCM message (may be fragmented)
}

GpsRtcmData struct (generated typeinfo) RTCM message for injecting into the onboard GPS (used for DGPS)

func (*GpsRtcmData) Dict

func (m *GpsRtcmData) Dict() map[string]interface{}

ToMap (generated function)

func (*GpsRtcmData) Marshal

func (m *GpsRtcmData) Marshal() ([]byte, error)

Marshal (generated function)

func (GpsRtcmData) MarshalEasyJSON added in v1.5.0

func (v GpsRtcmData) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GpsRtcmData) MarshalJSON added in v1.5.0

func (v GpsRtcmData) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GpsRtcmData) MsgID

func (m *GpsRtcmData) MsgID() message.MessageID

MsgID (generated function)

func (*GpsRtcmData) String

func (m *GpsRtcmData) String() string

String (generated function)

func (*GpsRtcmData) Unmarshal

func (m *GpsRtcmData) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GpsRtcmData) UnmarshalEasyJSON added in v1.5.0

func (v *GpsRtcmData) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GpsRtcmData) UnmarshalJSON added in v1.5.0

func (v *GpsRtcmData) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GpsRtk

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

GpsRtk struct (generated typeinfo) RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting

func (*GpsRtk) Dict

func (m *GpsRtk) Dict() map[string]interface{}

ToMap (generated function)

func (*GpsRtk) Marshal

func (m *GpsRtk) Marshal() ([]byte, error)

Marshal (generated function)

func (GpsRtk) MarshalEasyJSON added in v1.5.0

func (v GpsRtk) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GpsRtk) MarshalJSON added in v1.5.0

func (v GpsRtk) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GpsRtk) MsgID

func (m *GpsRtk) MsgID() message.MessageID

MsgID (generated function)

func (*GpsRtk) String

func (m *GpsRtk) String() string

String (generated function)

func (*GpsRtk) Unmarshal

func (m *GpsRtk) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GpsRtk) UnmarshalEasyJSON added in v1.5.0

func (v *GpsRtk) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GpsRtk) UnmarshalJSON added in v1.5.0

func (v *GpsRtk) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type GpsStatus

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

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

func (*GpsStatus) Dict

func (m *GpsStatus) Dict() map[string]interface{}

ToMap (generated function)

func (*GpsStatus) Marshal

func (m *GpsStatus) Marshal() ([]byte, error)

Marshal (generated function)

func (GpsStatus) MarshalEasyJSON added in v1.5.0

func (v GpsStatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (GpsStatus) MarshalJSON added in v1.5.0

func (v GpsStatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*GpsStatus) MsgID

func (m *GpsStatus) MsgID() message.MessageID

MsgID (generated function)

func (*GpsStatus) String

func (m *GpsStatus) String() string

String (generated function)

func (*GpsStatus) Unmarshal

func (m *GpsStatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*GpsStatus) UnmarshalEasyJSON added in v1.5.0

func (v *GpsStatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*GpsStatus) UnmarshalJSON added in v1.5.0

func (v *GpsStatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type HEADING_TYPE

type HEADING_TYPE int

HEADING_TYPE type

const (
	// HEADING_TYPE_COURSE_OVER_GROUND enum
	HEADING_TYPE_COURSE_OVER_GROUND HEADING_TYPE = 0
	// HEADING_TYPE_HEADING enum
	HEADING_TYPE_HEADING HEADING_TYPE = 1
)

func (HEADING_TYPE) Bitmask

func (e HEADING_TYPE) Bitmask() string

Bitmask return string representetion of intersects HEADING_TYPE enums

func (HEADING_TYPE) MarshalBinary

func (e HEADING_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (HEADING_TYPE) String

func (e HEADING_TYPE) String() string

func (*HEADING_TYPE) UnmarshalBinary

func (e *HEADING_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type HL_FAILURE_FLAG

type HL_FAILURE_FLAG int

HL_FAILURE_FLAG type. Flags to report failure cases over the high latency telemtry.

const (
	// HL_FAILURE_FLAG_GPS enum. GPS failure
	HL_FAILURE_FLAG_GPS HL_FAILURE_FLAG = 1
	// HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE enum. Differential pressure sensor failure
	HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE HL_FAILURE_FLAG = 2
	// HL_FAILURE_FLAG_ABSOLUTE_PRESSURE enum. Absolute pressure sensor failure
	HL_FAILURE_FLAG_ABSOLUTE_PRESSURE HL_FAILURE_FLAG = 4
	// HL_FAILURE_FLAG_3D_ACCEL enum. Accelerometer sensor failure
	HL_FAILURE_FLAG_3D_ACCEL HL_FAILURE_FLAG = 8
	// HL_FAILURE_FLAG_3D_GYRO enum. Gyroscope sensor failure
	HL_FAILURE_FLAG_3D_GYRO HL_FAILURE_FLAG = 16
	// HL_FAILURE_FLAG_3D_MAG enum. Magnetometer sensor failure
	HL_FAILURE_FLAG_3D_MAG HL_FAILURE_FLAG = 32
	// HL_FAILURE_FLAG_TERRAIN enum. Terrain subsystem failure
	HL_FAILURE_FLAG_TERRAIN HL_FAILURE_FLAG = 64
	// HL_FAILURE_FLAG_BATTERY enum. Battery failure/critical low battery
	HL_FAILURE_FLAG_BATTERY HL_FAILURE_FLAG = 128
	// HL_FAILURE_FLAG_RC_RECEIVER enum. RC receiver failure/no rc connection
	HL_FAILURE_FLAG_RC_RECEIVER HL_FAILURE_FLAG = 256
	// HL_FAILURE_FLAG_OFFBOARD_LINK enum. Offboard link failure
	HL_FAILURE_FLAG_OFFBOARD_LINK HL_FAILURE_FLAG = 512
	// HL_FAILURE_FLAG_ENGINE enum. Engine failure
	HL_FAILURE_FLAG_ENGINE HL_FAILURE_FLAG = 1024
	// HL_FAILURE_FLAG_GEOFENCE enum. Geofence violation
	HL_FAILURE_FLAG_GEOFENCE HL_FAILURE_FLAG = 2048
	// HL_FAILURE_FLAG_ESTIMATOR enum. Estimator failure, for example measurement rejection or large variances
	HL_FAILURE_FLAG_ESTIMATOR HL_FAILURE_FLAG = 4096
	// HL_FAILURE_FLAG_MISSION enum. Mission failure
	HL_FAILURE_FLAG_MISSION HL_FAILURE_FLAG = 8192
)

func (HL_FAILURE_FLAG) Bitmask

func (e HL_FAILURE_FLAG) Bitmask() string

Bitmask return string representetion of intersects HL_FAILURE_FLAG enums

func (HL_FAILURE_FLAG) MarshalBinary

func (e HL_FAILURE_FLAG) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (HL_FAILURE_FLAG) String

func (e HL_FAILURE_FLAG) String() string

func (*HL_FAILURE_FLAG) UnmarshalBinary

func (e *HL_FAILURE_FLAG) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type Heartbeat

type Heartbeat struct {
	CustomMode     uint32        `json:"CustomMode" `     // A bitfield for use for autopilot-specific flags
	Type           MAV_TYPE      `json:"Type" `           // Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.
	Autopilot      MAV_AUTOPILOT `json:"Autopilot" `      // Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
	BaseMode       MAV_MODE_FLAG `json:"BaseMode" `       // System mode bitmap.
	SystemStatus   MAV_STATE     `json:"SystemStatus" `   // System status flag.
	MavlinkVersion uint8         `json:"MavlinkVersion" ` // MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version
}

Heartbeat struct (generated typeinfo) The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at https://mavlink.io/en/services/heartbeat.html

func (*Heartbeat) Dict

func (m *Heartbeat) Dict() map[string]interface{}

ToMap (generated function)

func (*Heartbeat) Marshal

func (m *Heartbeat) Marshal() ([]byte, error)

Marshal (generated function)

func (Heartbeat) MarshalEasyJSON added in v1.5.0

func (v Heartbeat) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Heartbeat) MarshalJSON added in v1.5.0

func (v Heartbeat) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Heartbeat) MsgID

func (m *Heartbeat) MsgID() message.MessageID

MsgID (generated function)

func (*Heartbeat) String

func (m *Heartbeat) String() string

String (generated function)

func (*Heartbeat) Unmarshal

func (m *Heartbeat) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Heartbeat) UnmarshalEasyJSON added in v1.5.0

func (v *Heartbeat) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Heartbeat) UnmarshalJSON added in v1.5.0

func (v *Heartbeat) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type HighLatency

type HighLatency struct {
	CustomMode       uint32           `json:"CustomMode" `       // A bitfield for use for autopilot-specific flags.
	Latitude         int32            `json:"Latitude" `         // [ degE7 ] Latitude
	Longitude        int32            `json:"Longitude" `        // [ degE7 ] Longitude
	Roll             int16            `json:"Roll" `             // [ cdeg ] roll
	Pitch            int16            `json:"Pitch" `            // [ cdeg ] pitch
	Heading          uint16           `json:"Heading" `          // [ cdeg ] heading
	HeadingSp        int16            `json:"HeadingSp" `        // [ cdeg ] heading setpoint
	AltitudeAmsl     int16            `json:"AltitudeAmsl" `     // [ m ] Altitude above mean sea level
	AltitudeSp       int16            `json:"AltitudeSp" `       // [ m ] Altitude setpoint relative to the home position
	WpDistance       uint16           `json:"WpDistance" `       // [ m ] distance to target
	BaseMode         MAV_MODE_FLAG    `json:"BaseMode" `         // Bitmap of enabled system modes.
	LandedState      MAV_LANDED_STATE `json:"LandedState" `      // The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
	Throttle         int8             `json:"Throttle" `         // [ % ] throttle (percentage)
	Airspeed         uint8            `json:"Airspeed" `         // [ m/s ] airspeed
	AirspeedSp       uint8            `json:"AirspeedSp" `       // [ m/s ] airspeed setpoint
	Groundspeed      uint8            `json:"Groundspeed" `      // [ m/s ] groundspeed
	ClimbRate        int8             `json:"ClimbRate" `        // [ m/s ] climb rate
	GpsNsat          uint8            `json:"GpsNsat" `          // Number of satellites visible. If unknown, set to 255
	GpsFixType       GPS_FIX_TYPE     `json:"GpsFixType" `       // GPS Fix type.
	BatteryRemaining uint8            `json:"BatteryRemaining" ` // [ % ] Remaining battery (percentage)
	Temperature      int8             `json:"Temperature" `      // [ degC ] Autopilot temperature (degrees C)
	TemperatureAir   int8             `json:"TemperatureAir" `   // [ degC ] Air temperature (degrees C) from airspeed sensor
	Failsafe         uint8            `json:"Failsafe" `         // failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)
	WpNum            uint8            `json:"WpNum" `            // current waypoint number
}

HighLatency struct (generated typeinfo) Message appropriate for high latency connections like Iridium

func (*HighLatency) Dict

func (m *HighLatency) Dict() map[string]interface{}

ToMap (generated function)

func (*HighLatency) Marshal

func (m *HighLatency) Marshal() ([]byte, error)

Marshal (generated function)

func (HighLatency) MarshalEasyJSON added in v1.5.0

func (v HighLatency) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (HighLatency) MarshalJSON added in v1.5.0

func (v HighLatency) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*HighLatency) MsgID

func (m *HighLatency) MsgID() message.MessageID

MsgID (generated function)

func (*HighLatency) String

func (m *HighLatency) String() string

String (generated function)

func (*HighLatency) Unmarshal

func (m *HighLatency) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*HighLatency) UnmarshalEasyJSON added in v1.5.0

func (v *HighLatency) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*HighLatency) UnmarshalJSON added in v1.5.0

func (v *HighLatency) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type HighLatency2

type HighLatency2 struct {
	Timestamp      uint32          `json:"Timestamp" `      // [ ms ] Timestamp (milliseconds since boot or Unix epoch)
	Latitude       int32           `json:"Latitude" `       // [ degE7 ] Latitude
	Longitude      int32           `json:"Longitude" `      // [ degE7 ] Longitude
	CustomMode     uint16          `json:"CustomMode" `     // A bitfield for use for autopilot-specific flags (2 byte version).
	Altitude       int16           `json:"Altitude" `       // [ m ] Altitude above mean sea level
	TargetAltitude int16           `json:"TargetAltitude" ` // [ m ] Altitude setpoint
	TargetDistance uint16          `json:"TargetDistance" ` // [ dam ] Distance to target waypoint or position
	WpNum          uint16          `json:"WpNum" `          // Current waypoint number
	FailureFlags   HL_FAILURE_FLAG `json:"FailureFlags" `   // Bitmap of failure flags.
	Type           MAV_TYPE        `json:"Type" `           // Type of the MAV (quadrotor, helicopter, etc.)
	Autopilot      MAV_AUTOPILOT   `json:"Autopilot" `      // Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
	Heading        uint8           `json:"Heading" `        // [ deg/2 ] Heading
	TargetHeading  uint8           `json:"TargetHeading" `  // [ deg/2 ] Heading setpoint
	Throttle       uint8           `json:"Throttle" `       // [ % ] Throttle
	Airspeed       uint8           `json:"Airspeed" `       // [ m/s*5 ] Airspeed
	AirspeedSp     uint8           `json:"AirspeedSp" `     // [ m/s*5 ] Airspeed setpoint
	Groundspeed    uint8           `json:"Groundspeed" `    // [ m/s*5 ] Groundspeed
	Windspeed      uint8           `json:"Windspeed" `      // [ m/s*5 ] Windspeed
	WindHeading    uint8           `json:"WindHeading" `    // [ deg/2 ] Wind heading
	Eph            uint8           `json:"Eph" `            // [ dm ] Maximum error horizontal position since last message
	Epv            uint8           `json:"Epv" `            // [ dm ] Maximum error vertical position since last message
	TemperatureAir int8            `json:"TemperatureAir" ` // [ degC ] Air temperature from airspeed sensor
	ClimbRate      int8            `json:"ClimbRate" `      // [ dm/s ] Maximum climb rate magnitude since last message
	Battery        int8            `json:"Battery" `        // [ % ] Battery level (-1 if field not provided).
	Custom0        int8            `json:"Custom0" `        // Field for custom payload.
	Custom1        int8            `json:"Custom1" `        // Field for custom payload.
	Custom2        int8            `json:"Custom2" `        // Field for custom payload.
}

HighLatency2 struct (generated typeinfo) Message appropriate for high latency connections like Iridium (version 2)

func (*HighLatency2) Dict

func (m *HighLatency2) Dict() map[string]interface{}

ToMap (generated function)

func (*HighLatency2) Marshal

func (m *HighLatency2) Marshal() ([]byte, error)

Marshal (generated function)

func (HighLatency2) MarshalEasyJSON added in v1.5.0

func (v HighLatency2) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (HighLatency2) MarshalJSON added in v1.5.0

func (v HighLatency2) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*HighLatency2) MsgID

func (m *HighLatency2) MsgID() message.MessageID

MsgID (generated function)

func (*HighLatency2) String

func (m *HighLatency2) String() string

String (generated function)

func (*HighLatency2) Unmarshal

func (m *HighLatency2) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*HighLatency2) UnmarshalEasyJSON added in v1.5.0

func (v *HighLatency2) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*HighLatency2) UnmarshalJSON added in v1.5.0

func (v *HighLatency2) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type HighresImu

type HighresImu struct {
	TimeUsec      uint64  `json:"TimeUsec" `      // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Xacc          float32 `json:"Xacc" `          // [ m/s/s ] X acceleration
	Yacc          float32 `json:"Yacc" `          // [ m/s/s ] Y acceleration
	Zacc          float32 `json:"Zacc" `          // [ m/s/s ] Z acceleration
	Xgyro         float32 `json:"Xgyro" `         // [ rad/s ] Angular speed around X axis
	Ygyro         float32 `json:"Ygyro" `         // [ rad/s ] Angular speed around Y axis
	Zgyro         float32 `json:"Zgyro" `         // [ rad/s ] Angular speed around Z axis
	Xmag          float32 `json:"Xmag" `          // [ gauss ] X Magnetic field
	Ymag          float32 `json:"Ymag" `          // [ gauss ] Y Magnetic field
	Zmag          float32 `json:"Zmag" `          // [ gauss ] Z Magnetic field
	AbsPressure   float32 `json:"AbsPressure" `   // [ hPa ] Absolute pressure
	DiffPressure  float32 `json:"DiffPressure" `  // [ hPa ] Differential pressure
	PressureAlt   float32 `json:"PressureAlt" `   // Altitude calculated from pressure
	Temperature   float32 `json:"Temperature" `   // [ degC ] Temperature
	FieldsUpdated uint16  `json:"FieldsUpdated" ` // Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
}

HighresImu struct (generated typeinfo) The IMU readings in SI units in NED body frame

func (*HighresImu) Dict

func (m *HighresImu) Dict() map[string]interface{}

ToMap (generated function)

func (*HighresImu) Marshal

func (m *HighresImu) Marshal() ([]byte, error)

Marshal (generated function)

func (HighresImu) MarshalEasyJSON added in v1.5.0

func (v HighresImu) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (HighresImu) MarshalJSON added in v1.5.0

func (v HighresImu) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*HighresImu) MsgID

func (m *HighresImu) MsgID() message.MessageID

MsgID (generated function)

func (*HighresImu) String

func (m *HighresImu) String() string

String (generated function)

func (*HighresImu) Unmarshal

func (m *HighresImu) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*HighresImu) UnmarshalEasyJSON added in v1.5.0

func (v *HighresImu) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*HighresImu) UnmarshalJSON added in v1.5.0

func (v *HighresImu) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type HilActuatorControls

type HilActuatorControls struct {
	TimeUsec uint64        `json:"TimeUsec" `          // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Flags    uint64        `json:"Flags" `             // Flags as bitfield, 1: indicate simulation using lockstep.
	Controls []float32     `json:"Controls" len:"16" ` // Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.
	Mode     MAV_MODE_FLAG `json:"Mode" `              // System mode. Includes arming state.
}

HilActuatorControls struct (generated typeinfo) Sent from autopilot to simulation. Hardware in the loop control outputs (replacement for HIL_CONTROLS)

func (*HilActuatorControls) Dict

func (m *HilActuatorControls) Dict() map[string]interface{}

ToMap (generated function)

func (*HilActuatorControls) Marshal

func (m *HilActuatorControls) Marshal() ([]byte, error)

Marshal (generated function)

func (HilActuatorControls) MarshalEasyJSON added in v1.5.0

func (v HilActuatorControls) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (HilActuatorControls) MarshalJSON added in v1.5.0

func (v HilActuatorControls) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*HilActuatorControls) MsgID

MsgID (generated function)

func (*HilActuatorControls) String

func (m *HilActuatorControls) String() string

String (generated function)

func (*HilActuatorControls) Unmarshal

func (m *HilActuatorControls) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*HilActuatorControls) UnmarshalEasyJSON added in v1.5.0

func (v *HilActuatorControls) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*HilActuatorControls) UnmarshalJSON added in v1.5.0

func (v *HilActuatorControls) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type HilControls

type HilControls struct {
	TimeUsec      uint64   `json:"TimeUsec" `      // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	RollAilerons  float32  `json:"RollAilerons" `  // Control output -1 .. 1
	PitchElevator float32  `json:"PitchElevator" ` // Control output -1 .. 1
	YawRudder     float32  `json:"YawRudder" `     // Control output -1 .. 1
	Throttle      float32  `json:"Throttle" `      // Throttle 0 .. 1
	Aux1          float32  `json:"Aux1" `          // Aux 1, -1 .. 1
	Aux2          float32  `json:"Aux2" `          // Aux 2, -1 .. 1
	Aux3          float32  `json:"Aux3" `          // Aux 3, -1 .. 1
	Aux4          float32  `json:"Aux4" `          // Aux 4, -1 .. 1
	Mode          MAV_MODE `json:"Mode" `          // System mode.
	NavMode       uint8    `json:"NavMode" `       // Navigation mode (MAV_NAV_MODE)
}

HilControls struct (generated typeinfo) Sent from autopilot to simulation. Hardware in the loop control outputs

func (*HilControls) Dict

func (m *HilControls) Dict() map[string]interface{}

ToMap (generated function)

func (*HilControls) Marshal

func (m *HilControls) Marshal() ([]byte, error)

Marshal (generated function)

func (HilControls) MarshalEasyJSON added in v1.5.0

func (v HilControls) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (HilControls) MarshalJSON added in v1.5.0

func (v HilControls) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*HilControls) MsgID

func (m *HilControls) MsgID() message.MessageID

MsgID (generated function)

func (*HilControls) String

func (m *HilControls) String() string

String (generated function)

func (*HilControls) Unmarshal

func (m *HilControls) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*HilControls) UnmarshalEasyJSON added in v1.5.0

func (v *HilControls) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*HilControls) UnmarshalJSON added in v1.5.0

func (v *HilControls) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type HilGps

type HilGps struct {
	TimeUsec          uint64 `json:"TimeUsec" `          // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Lat               int32  `json:"Lat" `               // [ degE7 ] Latitude (WGS84)
	Lon               int32  `json:"Lon" `               // [ degE7 ] Longitude (WGS84)
	Alt               int32  `json:"Alt" `               // [ mm ] Altitude (MSL). Positive for up.
	Eph               uint16 `json:"Eph" `               // GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
	Epv               uint16 `json:"Epv" `               // GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
	Vel               uint16 `json:"Vel" `               // [ cm/s ] GPS ground speed. If unknown, set to: 65535
	Vn                int16  `json:"Vn" `                // [ cm/s ] GPS velocity in north direction in earth-fixed NED frame
	Ve                int16  `json:"Ve" `                // [ cm/s ] GPS velocity in east direction in earth-fixed NED frame
	Vd                int16  `json:"Vd" `                // [ cm/s ] GPS velocity in down direction in earth-fixed NED frame
	Cog               uint16 `json:"Cog" `               // [ cdeg ] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535
	FixType           uint8  `json:"FixType" `           // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
	SatellitesVisible uint8  `json:"SatellitesVisible" ` // Number of satellites visible. If unknown, set to 255
}

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

NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate.

func (*HilGps) Dict

func (m *HilGps) Dict() map[string]interface{}

ToMap (generated function)

func (*HilGps) Marshal

func (m *HilGps) Marshal() ([]byte, error)

Marshal (generated function)

func (HilGps) MarshalEasyJSON added in v1.5.0

func (v HilGps) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (HilGps) MarshalJSON added in v1.5.0

func (v HilGps) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*HilGps) MsgID

func (m *HilGps) MsgID() message.MessageID

MsgID (generated function)

func (*HilGps) String

func (m *HilGps) String() string

String (generated function)

func (*HilGps) Unmarshal

func (m *HilGps) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*HilGps) UnmarshalEasyJSON added in v1.5.0

func (v *HilGps) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*HilGps) UnmarshalJSON added in v1.5.0

func (v *HilGps) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type HilOpticalFlow

type HilOpticalFlow struct {
	TimeUsec            uint64  `json:"TimeUsec" `            // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	IntegrationTimeUs   uint32  `json:"IntegrationTimeUs" `   // [ us ] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
	IntegratedX         float32 `json:"IntegratedX" `         // [ rad ] Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
	IntegratedY         float32 `json:"IntegratedY" `         // [ rad ] Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
	IntegratedXgyro     float32 `json:"IntegratedXgyro" `     // [ rad ] RH rotation around X axis
	IntegratedYgyro     float32 `json:"IntegratedYgyro" `     // [ rad ] RH rotation around Y axis
	IntegratedZgyro     float32 `json:"IntegratedZgyro" `     // [ rad ] RH rotation around Z axis
	TimeDeltaDistanceUs uint32  `json:"TimeDeltaDistanceUs" ` // [ us ] Time since the distance was sampled.
	Distance            float32 `json:"Distance" `            // [ m ] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
	Temperature         int16   `json:"Temperature" `         // [ cdegC ] Temperature
	SensorID            uint8   `json:"SensorID" `            // Sensor ID
	Quality             uint8   `json:"Quality" `             // Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
}

HilOpticalFlow struct (generated typeinfo) Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor)

func (*HilOpticalFlow) Dict

func (m *HilOpticalFlow) Dict() map[string]interface{}

ToMap (generated function)

func (*HilOpticalFlow) Marshal

func (m *HilOpticalFlow) Marshal() ([]byte, error)

Marshal (generated function)

func (HilOpticalFlow) MarshalEasyJSON added in v1.5.0

func (v HilOpticalFlow) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (HilOpticalFlow) MarshalJSON added in v1.5.0

func (v HilOpticalFlow) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*HilOpticalFlow) MsgID

func (m *HilOpticalFlow) MsgID() message.MessageID

MsgID (generated function)

func (*HilOpticalFlow) String

func (m *HilOpticalFlow) String() string

String (generated function)

func (*HilOpticalFlow) Unmarshal

func (m *HilOpticalFlow) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*HilOpticalFlow) UnmarshalEasyJSON added in v1.5.0

func (v *HilOpticalFlow) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*HilOpticalFlow) UnmarshalJSON added in v1.5.0

func (v *HilOpticalFlow) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type HilRcInputsRaw

type HilRcInputsRaw struct {
	TimeUsec  uint64 `json:"TimeUsec" `  // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Chan1Raw  uint16 `json:"Chan1Raw" `  // [ us ] RC channel 1 value
	Chan2Raw  uint16 `json:"Chan2Raw" `  // [ us ] RC channel 2 value
	Chan3Raw  uint16 `json:"Chan3Raw" `  // [ us ] RC channel 3 value
	Chan4Raw  uint16 `json:"Chan4Raw" `  // [ us ] RC channel 4 value
	Chan5Raw  uint16 `json:"Chan5Raw" `  // [ us ] RC channel 5 value
	Chan6Raw  uint16 `json:"Chan6Raw" `  // [ us ] RC channel 6 value
	Chan7Raw  uint16 `json:"Chan7Raw" `  // [ us ] RC channel 7 value
	Chan8Raw  uint16 `json:"Chan8Raw" `  // [ us ] RC channel 8 value
	Chan9Raw  uint16 `json:"Chan9Raw" `  // [ us ] RC channel 9 value
	Chan10Raw uint16 `json:"Chan10Raw" ` // [ us ] RC channel 10 value
	Chan11Raw uint16 `json:"Chan11Raw" ` // [ us ] RC channel 11 value
	Chan12Raw uint16 `json:"Chan12Raw" ` // [ us ] RC channel 12 value
	Rssi      uint8  `json:"Rssi" `      // Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.
}

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

func (*HilRcInputsRaw) Dict

func (m *HilRcInputsRaw) Dict() map[string]interface{}

ToMap (generated function)

func (*HilRcInputsRaw) Marshal

func (m *HilRcInputsRaw) Marshal() ([]byte, error)

Marshal (generated function)

func (HilRcInputsRaw) MarshalEasyJSON added in v1.5.0

func (v HilRcInputsRaw) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (HilRcInputsRaw) MarshalJSON added in v1.5.0

func (v HilRcInputsRaw) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*HilRcInputsRaw) MsgID

func (m *HilRcInputsRaw) MsgID() message.MessageID

MsgID (generated function)

func (*HilRcInputsRaw) String

func (m *HilRcInputsRaw) String() string

String (generated function)

func (*HilRcInputsRaw) Unmarshal

func (m *HilRcInputsRaw) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*HilRcInputsRaw) UnmarshalEasyJSON added in v1.5.0

func (v *HilRcInputsRaw) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*HilRcInputsRaw) UnmarshalJSON added in v1.5.0

func (v *HilRcInputsRaw) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type HilSensor

type HilSensor struct {
	TimeUsec      uint64  `json:"TimeUsec" `      // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Xacc          float32 `json:"Xacc" `          // [ m/s/s ] X acceleration
	Yacc          float32 `json:"Yacc" `          // [ m/s/s ] Y acceleration
	Zacc          float32 `json:"Zacc" `          // [ m/s/s ] Z acceleration
	Xgyro         float32 `json:"Xgyro" `         // [ rad/s ] Angular speed around X axis in body frame
	Ygyro         float32 `json:"Ygyro" `         // [ rad/s ] Angular speed around Y axis in body frame
	Zgyro         float32 `json:"Zgyro" `         // [ rad/s ] Angular speed around Z axis in body frame
	Xmag          float32 `json:"Xmag" `          // [ gauss ] X Magnetic field
	Ymag          float32 `json:"Ymag" `          // [ gauss ] Y Magnetic field
	Zmag          float32 `json:"Zmag" `          // [ gauss ] Z Magnetic field
	AbsPressure   float32 `json:"AbsPressure" `   // [ hPa ] Absolute pressure
	DiffPressure  float32 `json:"DiffPressure" `  // [ hPa ] Differential pressure (airspeed)
	PressureAlt   float32 `json:"PressureAlt" `   // Altitude calculated from pressure
	Temperature   float32 `json:"Temperature" `   // [ degC ] Temperature
	FieldsUpdated uint32  `json:"FieldsUpdated" ` // Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.
}

HilSensor struct (generated typeinfo) The IMU readings in SI units in NED body frame

func (*HilSensor) Dict

func (m *HilSensor) Dict() map[string]interface{}

ToMap (generated function)

func (*HilSensor) Marshal

func (m *HilSensor) Marshal() ([]byte, error)

Marshal (generated function)

func (HilSensor) MarshalEasyJSON added in v1.5.0

func (v HilSensor) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (HilSensor) MarshalJSON added in v1.5.0

func (v HilSensor) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*HilSensor) MsgID

func (m *HilSensor) MsgID() message.MessageID

MsgID (generated function)

func (*HilSensor) String

func (m *HilSensor) String() string

String (generated function)

func (*HilSensor) Unmarshal

func (m *HilSensor) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*HilSensor) UnmarshalEasyJSON added in v1.5.0

func (v *HilSensor) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*HilSensor) UnmarshalJSON added in v1.5.0

func (v *HilSensor) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type HilState

type HilState struct {
	TimeUsec   uint64  `json:"TimeUsec" `   // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Roll       float32 `json:"Roll" `       // [ rad ] Roll angle
	Pitch      float32 `json:"Pitch" `      // [ rad ] Pitch angle
	Yaw        float32 `json:"Yaw" `        // [ rad ] Yaw angle
	Rollspeed  float32 `json:"Rollspeed" `  // [ rad/s ] Body frame roll / phi angular speed
	Pitchspeed float32 `json:"Pitchspeed" ` // [ rad/s ] Body frame pitch / theta angular speed
	Yawspeed   float32 `json:"Yawspeed" `   // [ rad/s ] Body frame yaw / psi angular speed
	Lat        int32   `json:"Lat" `        // [ degE7 ] Latitude
	Lon        int32   `json:"Lon" `        // [ degE7 ] Longitude
	Alt        int32   `json:"Alt" `        // [ mm ] Altitude
	Vx         int16   `json:"Vx" `         // [ cm/s ] Ground X Speed (Latitude)
	Vy         int16   `json:"Vy" `         // [ cm/s ] Ground Y Speed (Longitude)
	Vz         int16   `json:"Vz" `         // [ cm/s ] Ground Z Speed (Altitude)
	Xacc       int16   `json:"Xacc" `       // [ mG ] X acceleration
	Yacc       int16   `json:"Yacc" `       // [ mG ] Y acceleration
	Zacc       int16   `json:"Zacc" `       // [ mG ] Z acceleration
}

HilState struct (generated typeinfo) Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations.

func (*HilState) Dict

func (m *HilState) Dict() map[string]interface{}

ToMap (generated function)

func (*HilState) Marshal

func (m *HilState) Marshal() ([]byte, error)

Marshal (generated function)

func (HilState) MarshalEasyJSON added in v1.5.0

func (v HilState) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (HilState) MarshalJSON added in v1.5.0

func (v HilState) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*HilState) MsgID

func (m *HilState) MsgID() message.MessageID

MsgID (generated function)

func (*HilState) String

func (m *HilState) String() string

String (generated function)

func (*HilState) Unmarshal

func (m *HilState) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*HilState) UnmarshalEasyJSON added in v1.5.0

func (v *HilState) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*HilState) UnmarshalJSON added in v1.5.0

func (v *HilState) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type HilStateQuaternion

type HilStateQuaternion struct {
	TimeUsec           uint64    `json:"TimeUsec" `                   // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	AttitudeQuaternion []float32 `json:"AttitudeQuaternion" len:"4" ` // Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
	Rollspeed          float32   `json:"Rollspeed" `                  // [ rad/s ] Body frame roll / phi angular speed
	Pitchspeed         float32   `json:"Pitchspeed" `                 // [ rad/s ] Body frame pitch / theta angular speed
	Yawspeed           float32   `json:"Yawspeed" `                   // [ rad/s ] Body frame yaw / psi angular speed
	Lat                int32     `json:"Lat" `                        // [ degE7 ] Latitude
	Lon                int32     `json:"Lon" `                        // [ degE7 ] Longitude
	Alt                int32     `json:"Alt" `                        // [ mm ] Altitude
	Vx                 int16     `json:"Vx" `                         // [ cm/s ] Ground X Speed (Latitude)
	Vy                 int16     `json:"Vy" `                         // [ cm/s ] Ground Y Speed (Longitude)
	Vz                 int16     `json:"Vz" `                         // [ cm/s ] Ground Z Speed (Altitude)
	IndAirspeed        uint16    `json:"IndAirspeed" `                // [ cm/s ] Indicated airspeed
	TrueAirspeed       uint16    `json:"TrueAirspeed" `               // [ cm/s ] True airspeed
	Xacc               int16     `json:"Xacc" `                       // [ mG ] X acceleration
	Yacc               int16     `json:"Yacc" `                       // [ mG ] Y acceleration
	Zacc               int16     `json:"Zacc" `                       // [ mG ] Z acceleration
}

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

func (*HilStateQuaternion) Dict

func (m *HilStateQuaternion) Dict() map[string]interface{}

ToMap (generated function)

func (*HilStateQuaternion) Marshal

func (m *HilStateQuaternion) Marshal() ([]byte, error)

Marshal (generated function)

func (HilStateQuaternion) MarshalEasyJSON added in v1.5.0

func (v HilStateQuaternion) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (HilStateQuaternion) MarshalJSON added in v1.5.0

func (v HilStateQuaternion) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*HilStateQuaternion) MsgID

MsgID (generated function)

func (*HilStateQuaternion) String

func (m *HilStateQuaternion) String() string

String (generated function)

func (*HilStateQuaternion) Unmarshal

func (m *HilStateQuaternion) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*HilStateQuaternion) UnmarshalEasyJSON added in v1.5.0

func (v *HilStateQuaternion) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*HilStateQuaternion) UnmarshalJSON added in v1.5.0

func (v *HilStateQuaternion) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type HomePosition

type HomePosition struct {
	Latitude  int32     `json:"Latitude" `  // [ degE7 ] Latitude (WGS84)
	Longitude int32     `json:"Longitude" ` // [ degE7 ] Longitude (WGS84)
	Altitude  int32     `json:"Altitude" `  // [ mm ] Altitude (MSL). Positive for up.
	X         float32   `json:"X" `         // [ m ] Local X position of this position in the local coordinate frame
	Y         float32   `json:"Y" `         // [ m ] Local Y position of this position in the local coordinate frame
	Z         float32   `json:"Z" `         // [ m ] Local Z position of this position in the local coordinate frame
	Q         []float32 `json:"Q" len:"4" ` // World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
	ApproachX float32   `json:"ApproachX" ` // [ m ] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
	ApproachY float32   `json:"ApproachY" ` // [ m ] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
	ApproachZ float32   `json:"ApproachZ" ` // [ m ] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
}

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

func (*HomePosition) Dict

func (m *HomePosition) Dict() map[string]interface{}

ToMap (generated function)

func (*HomePosition) Marshal

func (m *HomePosition) Marshal() ([]byte, error)

Marshal (generated function)

func (HomePosition) MarshalEasyJSON added in v1.5.0

func (v HomePosition) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (HomePosition) MarshalJSON added in v1.5.0

func (v HomePosition) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*HomePosition) MsgID

func (m *HomePosition) MsgID() message.MessageID

MsgID (generated function)

func (*HomePosition) String

func (m *HomePosition) String() string

String (generated function)

func (*HomePosition) Unmarshal

func (m *HomePosition) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*HomePosition) UnmarshalEasyJSON added in v1.5.0

func (v *HomePosition) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*HomePosition) UnmarshalJSON added in v1.5.0

func (v *HomePosition) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Hwstatus

type Hwstatus struct {
	Vcc    uint16 `json:"Vcc" `    // [ mV ] Board voltage.
	I2cerr uint8  `json:"I2cerr" ` // I2C error count.
}

Hwstatus struct (generated typeinfo) Status of key hardware.

func (*Hwstatus) Dict

func (m *Hwstatus) Dict() map[string]interface{}

ToMap (generated function)

func (*Hwstatus) Marshal

func (m *Hwstatus) Marshal() ([]byte, error)

Marshal (generated function)

func (Hwstatus) MarshalEasyJSON added in v1.5.0

func (v Hwstatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Hwstatus) MarshalJSON added in v1.5.0

func (v Hwstatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Hwstatus) MsgID

func (m *Hwstatus) MsgID() message.MessageID

MsgID (generated function)

func (*Hwstatus) String

func (m *Hwstatus) String() string

String (generated function)

func (*Hwstatus) Unmarshal

func (m *Hwstatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Hwstatus) UnmarshalEasyJSON added in v1.5.0

func (v *Hwstatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Hwstatus) UnmarshalJSON added in v1.5.0

func (v *Hwstatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ICAROUS_FMS_STATE

type ICAROUS_FMS_STATE int

ICAROUS_FMS_STATE type

const (
	// ICAROUS_FMS_STATE_IDLE enum
	ICAROUS_FMS_STATE_IDLE ICAROUS_FMS_STATE = 0
	// ICAROUS_FMS_STATE_TAKEOFF enum
	ICAROUS_FMS_STATE_TAKEOFF ICAROUS_FMS_STATE = 1
	// ICAROUS_FMS_STATE_CLIMB enum
	ICAROUS_FMS_STATE_CLIMB ICAROUS_FMS_STATE = 2
	// ICAROUS_FMS_STATE_CRUISE enum
	ICAROUS_FMS_STATE_CRUISE ICAROUS_FMS_STATE = 3
	// ICAROUS_FMS_STATE_APPROACH enum
	ICAROUS_FMS_STATE_APPROACH ICAROUS_FMS_STATE = 4
	// ICAROUS_FMS_STATE_LAND enum
	ICAROUS_FMS_STATE_LAND ICAROUS_FMS_STATE = 5
)

func (ICAROUS_FMS_STATE) Bitmask

func (e ICAROUS_FMS_STATE) Bitmask() string

Bitmask return string representetion of intersects ICAROUS_FMS_STATE enums

func (ICAROUS_FMS_STATE) MarshalBinary

func (e ICAROUS_FMS_STATE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (ICAROUS_FMS_STATE) String

func (e ICAROUS_FMS_STATE) String() string

func (*ICAROUS_FMS_STATE) UnmarshalBinary

func (e *ICAROUS_FMS_STATE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type ICAROUS_TRACK_BAND_TYPES

type ICAROUS_TRACK_BAND_TYPES int

ICAROUS_TRACK_BAND_TYPES type

const (
	// ICAROUS_TRACK_BAND_TYPE_NONE enum
	ICAROUS_TRACK_BAND_TYPE_NONE ICAROUS_TRACK_BAND_TYPES = 0
	// ICAROUS_TRACK_BAND_TYPE_NEAR enum
	ICAROUS_TRACK_BAND_TYPE_NEAR ICAROUS_TRACK_BAND_TYPES = 1
	// ICAROUS_TRACK_BAND_TYPE_RECOVERY enum
	ICAROUS_TRACK_BAND_TYPE_RECOVERY ICAROUS_TRACK_BAND_TYPES = 2
)

func (ICAROUS_TRACK_BAND_TYPES) Bitmask

func (e ICAROUS_TRACK_BAND_TYPES) Bitmask() string

Bitmask return string representetion of intersects ICAROUS_TRACK_BAND_TYPES enums

func (ICAROUS_TRACK_BAND_TYPES) MarshalBinary

func (e ICAROUS_TRACK_BAND_TYPES) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (ICAROUS_TRACK_BAND_TYPES) String

func (e ICAROUS_TRACK_BAND_TYPES) String() string

func (*ICAROUS_TRACK_BAND_TYPES) UnmarshalBinary

func (e *ICAROUS_TRACK_BAND_TYPES) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type LANDING_TARGET_TYPE

type LANDING_TARGET_TYPE int

LANDING_TARGET_TYPE type. Type of landing target

const (
	// LANDING_TARGET_TYPE_LIGHT_BEACON enum. Landing target signaled by light beacon (ex: IR-LOCK)
	LANDING_TARGET_TYPE_LIGHT_BEACON LANDING_TARGET_TYPE = 0
	// LANDING_TARGET_TYPE_RADIO_BEACON enum. Landing target signaled by radio beacon (ex: ILS, NDB)
	LANDING_TARGET_TYPE_RADIO_BEACON LANDING_TARGET_TYPE = 1
	// LANDING_TARGET_TYPE_VISION_FIDUCIAL enum. Landing target represented by a fiducial marker (ex: ARTag)
	LANDING_TARGET_TYPE_VISION_FIDUCIAL LANDING_TARGET_TYPE = 2
	// LANDING_TARGET_TYPE_VISION_OTHER enum. Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square)
	LANDING_TARGET_TYPE_VISION_OTHER LANDING_TARGET_TYPE = 3
)

func (LANDING_TARGET_TYPE) Bitmask

func (e LANDING_TARGET_TYPE) Bitmask() string

Bitmask return string representetion of intersects LANDING_TARGET_TYPE enums

func (LANDING_TARGET_TYPE) MarshalBinary

func (e LANDING_TARGET_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (LANDING_TARGET_TYPE) String

func (e LANDING_TARGET_TYPE) String() string

func (*LANDING_TARGET_TYPE) UnmarshalBinary

func (e *LANDING_TARGET_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type LED_CONTROL_PATTERN

type LED_CONTROL_PATTERN int

LED_CONTROL_PATTERN type

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

func (LED_CONTROL_PATTERN) Bitmask

func (e LED_CONTROL_PATTERN) Bitmask() string

Bitmask return string representetion of intersects LED_CONTROL_PATTERN enums

func (LED_CONTROL_PATTERN) MarshalBinary

func (e LED_CONTROL_PATTERN) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (LED_CONTROL_PATTERN) String

func (e LED_CONTROL_PATTERN) String() string

func (*LED_CONTROL_PATTERN) UnmarshalBinary

func (e *LED_CONTROL_PATTERN) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type LIMITS_STATE

type LIMITS_STATE int

LIMITS_STATE type

const (
	// LIMITS_INIT enum. Pre-initialization
	LIMITS_INIT LIMITS_STATE = 0
	// LIMITS_DISABLED enum. Disabled
	LIMITS_DISABLED LIMITS_STATE = 1
	// LIMITS_ENABLED enum. Checking limits
	LIMITS_ENABLED LIMITS_STATE = 2
	// LIMITS_TRIGGERED enum. A limit has been breached
	LIMITS_TRIGGERED LIMITS_STATE = 3
	// LIMITS_RECOVERING enum. Taking action e.g. Return/RTL
	LIMITS_RECOVERING LIMITS_STATE = 4
	// LIMITS_RECOVERED enum. We're no longer in breach of a limit
	LIMITS_RECOVERED LIMITS_STATE = 5
)

func (LIMITS_STATE) Bitmask

func (e LIMITS_STATE) Bitmask() string

Bitmask return string representetion of intersects LIMITS_STATE enums

func (LIMITS_STATE) MarshalBinary

func (e LIMITS_STATE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (LIMITS_STATE) String

func (e LIMITS_STATE) String() string

func (*LIMITS_STATE) UnmarshalBinary

func (e *LIMITS_STATE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type LIMIT_MODULE

type LIMIT_MODULE int

LIMIT_MODULE type

const (
	// LIMIT_GPSLOCK enum. Pre-initialization
	LIMIT_GPSLOCK LIMIT_MODULE = 1
	// LIMIT_GEOFENCE enum. Disabled
	LIMIT_GEOFENCE LIMIT_MODULE = 2
	// LIMIT_ALTITUDE enum. Checking limits
	LIMIT_ALTITUDE LIMIT_MODULE = 4
)

func (LIMIT_MODULE) Bitmask

func (e LIMIT_MODULE) Bitmask() string

Bitmask return string representetion of intersects LIMIT_MODULE enums

func (LIMIT_MODULE) MarshalBinary

func (e LIMIT_MODULE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (LIMIT_MODULE) String

func (e LIMIT_MODULE) String() string

func (*LIMIT_MODULE) UnmarshalBinary

func (e *LIMIT_MODULE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type LandingTarget

type LandingTarget struct {
	TimeUsec  uint64    `json:"TimeUsec" `  // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	AngleX    float32   `json:"AngleX" `    // [ rad ] X-axis angular offset of the target from the center of the image
	AngleY    float32   `json:"AngleY" `    // [ rad ] Y-axis angular offset of the target from the center of the image
	Distance  float32   `json:"Distance" `  // [ m ] Distance to the target from the vehicle
	SizeX     float32   `json:"SizeX" `     // [ rad ] Size of target along x-axis
	SizeY     float32   `json:"SizeY" `     // [ rad ] Size of target along y-axis
	TargetNum uint8     `json:"TargetNum" ` // The ID of the target if multiple targets are present
	Frame     MAV_FRAME `json:"Frame" `     // Coordinate frame used for following fields.
}

LandingTarget struct (generated typeinfo) The location of a landing target. See: https://mavlink.io/en/services/landing_target.html

func (*LandingTarget) Dict

func (m *LandingTarget) Dict() map[string]interface{}

ToMap (generated function)

func (*LandingTarget) Marshal

func (m *LandingTarget) Marshal() ([]byte, error)

Marshal (generated function)

func (LandingTarget) MarshalEasyJSON added in v1.5.0

func (v LandingTarget) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (LandingTarget) MarshalJSON added in v1.5.0

func (v LandingTarget) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*LandingTarget) MsgID

func (m *LandingTarget) MsgID() message.MessageID

MsgID (generated function)

func (*LandingTarget) String

func (m *LandingTarget) String() string

String (generated function)

func (*LandingTarget) Unmarshal

func (m *LandingTarget) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*LandingTarget) UnmarshalEasyJSON added in v1.5.0

func (v *LandingTarget) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*LandingTarget) UnmarshalJSON added in v1.5.0

func (v *LandingTarget) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type LedControl

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

LedControl struct (generated typeinfo) Control vehicle LEDs.

func (*LedControl) Dict

func (m *LedControl) Dict() map[string]interface{}

ToMap (generated function)

func (*LedControl) Marshal

func (m *LedControl) Marshal() ([]byte, error)

Marshal (generated function)

func (LedControl) MarshalEasyJSON added in v1.5.0

func (v LedControl) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (LedControl) MarshalJSON added in v1.5.0

func (v LedControl) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*LedControl) MsgID

func (m *LedControl) MsgID() message.MessageID

MsgID (generated function)

func (*LedControl) String

func (m *LedControl) String() string

String (generated function)

func (*LedControl) Unmarshal

func (m *LedControl) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*LedControl) UnmarshalEasyJSON added in v1.5.0

func (v *LedControl) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*LedControl) UnmarshalJSON added in v1.5.0

func (v *LedControl) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type LimitsStatus

type LimitsStatus struct {
	LastTrigger   uint32       `json:"LastTrigger" `   // [ ms ] Time (since boot) of last breach.
	LastAction    uint32       `json:"LastAction" `    // [ ms ] Time (since boot) of last recovery action.
	LastRecovery  uint32       `json:"LastRecovery" `  // [ ms ] Time (since boot) of last successful recovery.
	LastClear     uint32       `json:"LastClear" `     // [ ms ] Time (since boot) of last all-clear.
	BreachCount   uint16       `json:"BreachCount" `   // Number of fence breaches.
	LimitsState   LIMITS_STATE `json:"LimitsState" `   // State of AP_Limits.
	ModsEnabled   LIMIT_MODULE `json:"ModsEnabled" `   // AP_Limit_Module bitfield of enabled modules.
	ModsRequired  LIMIT_MODULE `json:"ModsRequired" `  // AP_Limit_Module bitfield of required modules.
	ModsTriggered LIMIT_MODULE `json:"ModsTriggered" ` // AP_Limit_Module bitfield of triggered modules.
}

LimitsStatus struct (generated typeinfo) Status of AP_Limits. Sent in extended status stream when AP_Limits is enabled.

func (*LimitsStatus) Dict

func (m *LimitsStatus) Dict() map[string]interface{}

ToMap (generated function)

func (*LimitsStatus) Marshal

func (m *LimitsStatus) Marshal() ([]byte, error)

Marshal (generated function)

func (LimitsStatus) MarshalEasyJSON added in v1.5.0

func (v LimitsStatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (LimitsStatus) MarshalJSON added in v1.5.0

func (v LimitsStatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*LimitsStatus) MsgID

func (m *LimitsStatus) MsgID() message.MessageID

MsgID (generated function)

func (*LimitsStatus) String

func (m *LimitsStatus) String() string

String (generated function)

func (*LimitsStatus) Unmarshal

func (m *LimitsStatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*LimitsStatus) UnmarshalEasyJSON added in v1.5.0

func (v *LimitsStatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*LimitsStatus) UnmarshalJSON added in v1.5.0

func (v *LimitsStatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type LinkNodeStatus

type LinkNodeStatus struct {
	Timestamp        uint64 `json:"Timestamp" `        // [ ms ] Timestamp (time since system boot).
	TxRate           uint32 `json:"TxRate" `           // [ bytes/s ] Transmit rate
	RxRate           uint32 `json:"RxRate" `           // [ bytes/s ] Receive rate
	MessagesSent     uint32 `json:"MessagesSent" `     // Messages sent
	MessagesReceived uint32 `json:"MessagesReceived" ` // Messages received (estimated from counting seq)
	MessagesLost     uint32 `json:"MessagesLost" `     // Messages lost (estimated from counting seq)
	RxParseErr       uint16 `json:"RxParseErr" `       // [ bytes ] Number of bytes that could not be parsed correctly.
	TxOverflows      uint16 `json:"TxOverflows" `      // [ bytes ] Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX
	RxOverflows      uint16 `json:"RxOverflows" `      // [ bytes ] Receive buffer overflows. This number wraps around as it reaches UINT16_MAX
	TxBuf            uint8  `json:"TxBuf" `            // [ % ] Remaining free transmit buffer space
	RxBuf            uint8  `json:"RxBuf" `            // [ % ] Remaining free receive buffer space
}

LinkNodeStatus struct (generated typeinfo) Status generated in each node in the communication chain and injected into MAVLink stream.

func (*LinkNodeStatus) Dict

func (m *LinkNodeStatus) Dict() map[string]interface{}

ToMap (generated function)

func (*LinkNodeStatus) Marshal

func (m *LinkNodeStatus) Marshal() ([]byte, error)

Marshal (generated function)

func (LinkNodeStatus) MarshalEasyJSON added in v1.5.0

func (v LinkNodeStatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (LinkNodeStatus) MarshalJSON added in v1.5.0

func (v LinkNodeStatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*LinkNodeStatus) MsgID

func (m *LinkNodeStatus) MsgID() message.MessageID

MsgID (generated function)

func (*LinkNodeStatus) String

func (m *LinkNodeStatus) String() string

String (generated function)

func (*LinkNodeStatus) Unmarshal

func (m *LinkNodeStatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*LinkNodeStatus) UnmarshalEasyJSON added in v1.5.0

func (v *LinkNodeStatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*LinkNodeStatus) UnmarshalJSON added in v1.5.0

func (v *LinkNodeStatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type LocalPositionNed

type LocalPositionNed struct {
	TimeBootMs uint32  `json:"TimeBootMs" ` // [ ms ] Timestamp (time since system boot).
	X          float32 `json:"X" `          // [ m ] X Position
	Y          float32 `json:"Y" `          // [ m ] Y Position
	Z          float32 `json:"Z" `          // [ m ] Z Position
	Vx         float32 `json:"Vx" `         // [ m/s ] X Speed
	Vy         float32 `json:"Vy" `         // [ m/s ] Y Speed
	Vz         float32 `json:"Vz" `         // [ m/s ] Z Speed
}

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

func (*LocalPositionNed) Dict

func (m *LocalPositionNed) Dict() map[string]interface{}

ToMap (generated function)

func (*LocalPositionNed) Marshal

func (m *LocalPositionNed) Marshal() ([]byte, error)

Marshal (generated function)

func (LocalPositionNed) MarshalEasyJSON added in v1.5.0

func (v LocalPositionNed) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (LocalPositionNed) MarshalJSON added in v1.5.0

func (v LocalPositionNed) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*LocalPositionNed) MsgID

func (m *LocalPositionNed) MsgID() message.MessageID

MsgID (generated function)

func (*LocalPositionNed) String

func (m *LocalPositionNed) String() string

String (generated function)

func (*LocalPositionNed) Unmarshal

func (m *LocalPositionNed) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*LocalPositionNed) UnmarshalEasyJSON added in v1.5.0

func (v *LocalPositionNed) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*LocalPositionNed) UnmarshalJSON added in v1.5.0

func (v *LocalPositionNed) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type LocalPositionNedCov

type LocalPositionNedCov struct {
	TimeUsec      uint64             `json:"TimeUsec" `            // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	X             float32            `json:"X" `                   // [ m ] X Position
	Y             float32            `json:"Y" `                   // [ m ] Y Position
	Z             float32            `json:"Z" `                   // [ m ] Z Position
	Vx            float32            `json:"Vx" `                  // [ m/s ] X Speed
	Vy            float32            `json:"Vy" `                  // [ m/s ] Y Speed
	Vz            float32            `json:"Vz" `                  // [ m/s ] Z Speed
	Ax            float32            `json:"Ax" `                  // [ m/s/s ] X Acceleration
	Ay            float32            `json:"Ay" `                  // [ m/s/s ] Y Acceleration
	Az            float32            `json:"Az" `                  // [ m/s/s ] Z Acceleration
	Covariance    []float32          `json:"Covariance" len:"45" ` // Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
	EstimatorType MAV_ESTIMATOR_TYPE `json:"EstimatorType" `       // Class id of the estimator this estimate originated from.
}

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

func (*LocalPositionNedCov) Dict

func (m *LocalPositionNedCov) Dict() map[string]interface{}

ToMap (generated function)

func (*LocalPositionNedCov) Marshal

func (m *LocalPositionNedCov) Marshal() ([]byte, error)

Marshal (generated function)

func (LocalPositionNedCov) MarshalEasyJSON added in v1.5.0

func (v LocalPositionNedCov) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (LocalPositionNedCov) MarshalJSON added in v1.5.0

func (v LocalPositionNedCov) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*LocalPositionNedCov) MsgID

MsgID (generated function)

func (*LocalPositionNedCov) String

func (m *LocalPositionNedCov) String() string

String (generated function)

func (*LocalPositionNedCov) Unmarshal

func (m *LocalPositionNedCov) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*LocalPositionNedCov) UnmarshalEasyJSON added in v1.5.0

func (v *LocalPositionNedCov) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*LocalPositionNedCov) UnmarshalJSON added in v1.5.0

func (v *LocalPositionNedCov) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type LocalPositionNedSystemGlobalOffset

type LocalPositionNedSystemGlobalOffset struct {
	TimeBootMs uint32  `json:"TimeBootMs" ` // [ ms ] Timestamp (time since system boot).
	X          float32 `json:"X" `          // [ m ] X Position
	Y          float32 `json:"Y" `          // [ m ] Y Position
	Z          float32 `json:"Z" `          // [ m ] Z Position
	Roll       float32 `json:"Roll" `       // [ rad ] Roll
	Pitch      float32 `json:"Pitch" `      // [ rad ] Pitch
	Yaw        float32 `json:"Yaw" `        // [ rad ] Yaw
}

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

func (*LocalPositionNedSystemGlobalOffset) Dict

func (m *LocalPositionNedSystemGlobalOffset) Dict() map[string]interface{}

ToMap (generated function)

func (*LocalPositionNedSystemGlobalOffset) Marshal

func (m *LocalPositionNedSystemGlobalOffset) Marshal() ([]byte, error)

Marshal (generated function)

func (LocalPositionNedSystemGlobalOffset) MarshalEasyJSON added in v1.5.0

func (v LocalPositionNedSystemGlobalOffset) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (LocalPositionNedSystemGlobalOffset) MarshalJSON added in v1.5.0

func (v LocalPositionNedSystemGlobalOffset) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*LocalPositionNedSystemGlobalOffset) MsgID

MsgID (generated function)

func (*LocalPositionNedSystemGlobalOffset) String

String (generated function)

func (*LocalPositionNedSystemGlobalOffset) Unmarshal

func (m *LocalPositionNedSystemGlobalOffset) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*LocalPositionNedSystemGlobalOffset) UnmarshalEasyJSON added in v1.5.0

func (v *LocalPositionNedSystemGlobalOffset) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*LocalPositionNedSystemGlobalOffset) UnmarshalJSON added in v1.5.0

func (v *LocalPositionNedSystemGlobalOffset) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type LogData

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

LogData struct (generated typeinfo) Reply to LOG_REQUEST_DATA

func (*LogData) Dict

func (m *LogData) Dict() map[string]interface{}

ToMap (generated function)

func (*LogData) Marshal

func (m *LogData) Marshal() ([]byte, error)

Marshal (generated function)

func (LogData) MarshalEasyJSON added in v1.5.0

func (v LogData) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (LogData) MarshalJSON added in v1.5.0

func (v LogData) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*LogData) MsgID

func (m *LogData) MsgID() message.MessageID

MsgID (generated function)

func (*LogData) String

func (m *LogData) String() string

String (generated function)

func (*LogData) Unmarshal

func (m *LogData) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*LogData) UnmarshalEasyJSON added in v1.5.0

func (v *LogData) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*LogData) UnmarshalJSON added in v1.5.0

func (v *LogData) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type LogEntry

type LogEntry struct {
	TimeUtc    uint32 `json:"TimeUtc" `    // [ s ] UTC timestamp of log since 1970, or 0 if not available
	Size       uint32 `json:"Size" `       // [ bytes ] Size of the log (may be approximate)
	ID         uint16 `json:"ID" `         // Log id
	NumLogs    uint16 `json:"NumLogs" `    // Total number of logs
	LastLogNum uint16 `json:"LastLogNum" ` // High log number
}

LogEntry struct (generated typeinfo) Reply to LOG_REQUEST_LIST

func (*LogEntry) Dict

func (m *LogEntry) Dict() map[string]interface{}

ToMap (generated function)

func (*LogEntry) Marshal

func (m *LogEntry) Marshal() ([]byte, error)

Marshal (generated function)

func (LogEntry) MarshalEasyJSON added in v1.5.0

func (v LogEntry) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (LogEntry) MarshalJSON added in v1.5.0

func (v LogEntry) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*LogEntry) MsgID

func (m *LogEntry) MsgID() message.MessageID

MsgID (generated function)

func (*LogEntry) String

func (m *LogEntry) String() string

String (generated function)

func (*LogEntry) Unmarshal

func (m *LogEntry) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*LogEntry) UnmarshalEasyJSON added in v1.5.0

func (v *LogEntry) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*LogEntry) UnmarshalJSON added in v1.5.0

func (v *LogEntry) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type LogErase

type LogErase struct {
	TargetSystem    uint8 `json:"TargetSystem" `    // System ID
	TargetComponent uint8 `json:"TargetComponent" ` // Component ID
}

LogErase struct (generated typeinfo) Erase all logs

func (*LogErase) Dict

func (m *LogErase) Dict() map[string]interface{}

ToMap (generated function)

func (*LogErase) Marshal

func (m *LogErase) Marshal() ([]byte, error)

Marshal (generated function)

func (LogErase) MarshalEasyJSON added in v1.5.0

func (v LogErase) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (LogErase) MarshalJSON added in v1.5.0

func (v LogErase) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*LogErase) MsgID

func (m *LogErase) MsgID() message.MessageID

MsgID (generated function)

func (*LogErase) String

func (m *LogErase) String() string

String (generated function)

func (*LogErase) Unmarshal

func (m *LogErase) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*LogErase) UnmarshalEasyJSON added in v1.5.0

func (v *LogErase) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*LogErase) UnmarshalJSON added in v1.5.0

func (v *LogErase) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type LogRequestData

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

LogRequestData struct (generated typeinfo) Request a chunk of a log

func (*LogRequestData) Dict

func (m *LogRequestData) Dict() map[string]interface{}

ToMap (generated function)

func (*LogRequestData) Marshal

func (m *LogRequestData) Marshal() ([]byte, error)

Marshal (generated function)

func (LogRequestData) MarshalEasyJSON added in v1.5.0

func (v LogRequestData) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (LogRequestData) MarshalJSON added in v1.5.0

func (v LogRequestData) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*LogRequestData) MsgID

func (m *LogRequestData) MsgID() message.MessageID

MsgID (generated function)

func (*LogRequestData) String

func (m *LogRequestData) String() string

String (generated function)

func (*LogRequestData) Unmarshal

func (m *LogRequestData) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*LogRequestData) UnmarshalEasyJSON added in v1.5.0

func (v *LogRequestData) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*LogRequestData) UnmarshalJSON added in v1.5.0

func (v *LogRequestData) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type LogRequestEnd

type LogRequestEnd struct {
	TargetSystem    uint8 `json:"TargetSystem" `    // System ID
	TargetComponent uint8 `json:"TargetComponent" ` // Component ID
}

LogRequestEnd struct (generated typeinfo) Stop log transfer and resume normal logging

func (*LogRequestEnd) Dict

func (m *LogRequestEnd) Dict() map[string]interface{}

ToMap (generated function)

func (*LogRequestEnd) Marshal

func (m *LogRequestEnd) Marshal() ([]byte, error)

Marshal (generated function)

func (LogRequestEnd) MarshalEasyJSON added in v1.5.0

func (v LogRequestEnd) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (LogRequestEnd) MarshalJSON added in v1.5.0

func (v LogRequestEnd) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*LogRequestEnd) MsgID

func (m *LogRequestEnd) MsgID() message.MessageID

MsgID (generated function)

func (*LogRequestEnd) String

func (m *LogRequestEnd) String() string

String (generated function)

func (*LogRequestEnd) Unmarshal

func (m *LogRequestEnd) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*LogRequestEnd) UnmarshalEasyJSON added in v1.5.0

func (v *LogRequestEnd) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*LogRequestEnd) UnmarshalJSON added in v1.5.0

func (v *LogRequestEnd) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type LogRequestList

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

LogRequestList struct (generated typeinfo) Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0.

func (*LogRequestList) Dict

func (m *LogRequestList) Dict() map[string]interface{}

ToMap (generated function)

func (*LogRequestList) Marshal

func (m *LogRequestList) Marshal() ([]byte, error)

Marshal (generated function)

func (LogRequestList) MarshalEasyJSON added in v1.5.0

func (v LogRequestList) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (LogRequestList) MarshalJSON added in v1.5.0

func (v LogRequestList) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*LogRequestList) MsgID

func (m *LogRequestList) MsgID() message.MessageID

MsgID (generated function)

func (*LogRequestList) String

func (m *LogRequestList) String() string

String (generated function)

func (*LogRequestList) Unmarshal

func (m *LogRequestList) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*LogRequestList) UnmarshalEasyJSON added in v1.5.0

func (v *LogRequestList) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*LogRequestList) UnmarshalJSON added in v1.5.0

func (v *LogRequestList) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MAG_CAL_STATUS

type MAG_CAL_STATUS int

MAG_CAL_STATUS type

const (
	// MAG_CAL_NOT_STARTED enum
	MAG_CAL_NOT_STARTED MAG_CAL_STATUS = 0
	// MAG_CAL_WAITING_TO_START enum
	MAG_CAL_WAITING_TO_START MAG_CAL_STATUS = 1
	// MAG_CAL_RUNNING_STEP_ONE enum
	MAG_CAL_RUNNING_STEP_ONE MAG_CAL_STATUS = 2
	// MAG_CAL_RUNNING_STEP_TWO enum
	MAG_CAL_RUNNING_STEP_TWO MAG_CAL_STATUS = 3
	// MAG_CAL_SUCCESS enum
	MAG_CAL_SUCCESS MAG_CAL_STATUS = 4
	// MAG_CAL_FAILED enum
	MAG_CAL_FAILED MAG_CAL_STATUS = 5
	// MAG_CAL_BAD_ORIENTATION enum
	MAG_CAL_BAD_ORIENTATION MAG_CAL_STATUS = 6
	// MAG_CAL_BAD_RADIUS enum
	MAG_CAL_BAD_RADIUS MAG_CAL_STATUS = 7
)

func (MAG_CAL_STATUS) Bitmask

func (e MAG_CAL_STATUS) Bitmask() string

Bitmask return string representetion of intersects MAG_CAL_STATUS enums

func (MAG_CAL_STATUS) MarshalBinary

func (e MAG_CAL_STATUS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAG_CAL_STATUS) String

func (e MAG_CAL_STATUS) String() string

func (*MAG_CAL_STATUS) UnmarshalBinary

func (e *MAG_CAL_STATUS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAVLINK_DATA_STREAM_TYPE int

MAVLINK_DATA_STREAM_TYPE type

const (
	// MAVLINK_DATA_STREAM_IMG_JPEG enum
	MAVLINK_DATA_STREAM_IMG_JPEG MAVLINK_DATA_STREAM_TYPE = 0
	// MAVLINK_DATA_STREAM_IMG_BMP enum
	MAVLINK_DATA_STREAM_IMG_BMP MAVLINK_DATA_STREAM_TYPE = 1
	// MAVLINK_DATA_STREAM_IMG_RAW8U enum
	MAVLINK_DATA_STREAM_IMG_RAW8U MAVLINK_DATA_STREAM_TYPE = 2
	// MAVLINK_DATA_STREAM_IMG_RAW32U enum
	MAVLINK_DATA_STREAM_IMG_RAW32U MAVLINK_DATA_STREAM_TYPE = 3
	// MAVLINK_DATA_STREAM_IMG_PGM enum
	MAVLINK_DATA_STREAM_IMG_PGM MAVLINK_DATA_STREAM_TYPE = 4
	// MAVLINK_DATA_STREAM_IMG_PNG enum
	MAVLINK_DATA_STREAM_IMG_PNG MAVLINK_DATA_STREAM_TYPE = 5
)
func (e MAVLINK_DATA_STREAM_TYPE) Bitmask() string

Bitmask return string representetion of intersects MAVLINK_DATA_STREAM_TYPE enums

func (e MAVLINK_DATA_STREAM_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (e MAVLINK_DATA_STREAM_TYPE) String() string
func (e *MAVLINK_DATA_STREAM_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ARM_AUTH_DENIED_REASON

type MAV_ARM_AUTH_DENIED_REASON int

MAV_ARM_AUTH_DENIED_REASON type

const (
	// MAV_ARM_AUTH_DENIED_REASON_GENERIC enum. Not a specific reason
	MAV_ARM_AUTH_DENIED_REASON_GENERIC MAV_ARM_AUTH_DENIED_REASON = 0
	// MAV_ARM_AUTH_DENIED_REASON_NONE enum. Authorizer will send the error as string to GCS
	MAV_ARM_AUTH_DENIED_REASON_NONE MAV_ARM_AUTH_DENIED_REASON = 1
	// MAV_ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT enum. At least one waypoint have a invalid value
	MAV_ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT MAV_ARM_AUTH_DENIED_REASON = 2
	// MAV_ARM_AUTH_DENIED_REASON_TIMEOUT enum. Timeout in the authorizer process(in case it depends on network)
	MAV_ARM_AUTH_DENIED_REASON_TIMEOUT MAV_ARM_AUTH_DENIED_REASON = 3
	// MAV_ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE enum. Airspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied
	MAV_ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE MAV_ARM_AUTH_DENIED_REASON = 4
	// MAV_ARM_AUTH_DENIED_REASON_BAD_WEATHER enum. Weather is not good to fly
	MAV_ARM_AUTH_DENIED_REASON_BAD_WEATHER MAV_ARM_AUTH_DENIED_REASON = 5
)

func (MAV_ARM_AUTH_DENIED_REASON) Bitmask

func (e MAV_ARM_AUTH_DENIED_REASON) Bitmask() string

Bitmask return string representetion of intersects MAV_ARM_AUTH_DENIED_REASON enums

func (MAV_ARM_AUTH_DENIED_REASON) MarshalBinary

func (e MAV_ARM_AUTH_DENIED_REASON) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ARM_AUTH_DENIED_REASON) String

func (*MAV_ARM_AUTH_DENIED_REASON) UnmarshalBinary

func (e *MAV_ARM_AUTH_DENIED_REASON) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_AUTOPILOT

type MAV_AUTOPILOT int

MAV_AUTOPILOT type. Micro air vehicle / autopilot classes. This identifies the individual model.

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

func (MAV_AUTOPILOT) Bitmask

func (e MAV_AUTOPILOT) Bitmask() string

Bitmask return string representetion of intersects MAV_AUTOPILOT enums

func (MAV_AUTOPILOT) MarshalBinary

func (e MAV_AUTOPILOT) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_AUTOPILOT) String

func (e MAV_AUTOPILOT) String() string

func (*MAV_AUTOPILOT) UnmarshalBinary

func (e *MAV_AUTOPILOT) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_BATTERY_CHARGE_STATE

type MAV_BATTERY_CHARGE_STATE int

MAV_BATTERY_CHARGE_STATE type. Enumeration for battery charge states.

const (
	// MAV_BATTERY_CHARGE_STATE_UNDEFINED enum. Low battery state is not provided
	MAV_BATTERY_CHARGE_STATE_UNDEFINED MAV_BATTERY_CHARGE_STATE = 0
	// MAV_BATTERY_CHARGE_STATE_OK enum. Battery is not in low state. Normal operation
	MAV_BATTERY_CHARGE_STATE_OK MAV_BATTERY_CHARGE_STATE = 1
	// MAV_BATTERY_CHARGE_STATE_LOW enum. Battery state is low, warn and monitor close
	MAV_BATTERY_CHARGE_STATE_LOW MAV_BATTERY_CHARGE_STATE = 2
	// MAV_BATTERY_CHARGE_STATE_CRITICAL enum. Battery state is critical, return or abort immediately
	MAV_BATTERY_CHARGE_STATE_CRITICAL MAV_BATTERY_CHARGE_STATE = 3
	// MAV_BATTERY_CHARGE_STATE_EMERGENCY enum. Battery state is too low for ordinary abort sequence. Perform fastest possible emergency stop to prevent damage
	MAV_BATTERY_CHARGE_STATE_EMERGENCY MAV_BATTERY_CHARGE_STATE = 4
	// MAV_BATTERY_CHARGE_STATE_FAILED enum. Battery failed, damage unavoidable. Possible causes (faults) are listed in MAV_BATTERY_FAULT
	MAV_BATTERY_CHARGE_STATE_FAILED MAV_BATTERY_CHARGE_STATE = 5
	// MAV_BATTERY_CHARGE_STATE_UNHEALTHY enum. Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in MAV_BATTERY_FAULT
	MAV_BATTERY_CHARGE_STATE_UNHEALTHY MAV_BATTERY_CHARGE_STATE = 6
	// MAV_BATTERY_CHARGE_STATE_CHARGING enum. Battery is charging
	MAV_BATTERY_CHARGE_STATE_CHARGING MAV_BATTERY_CHARGE_STATE = 7
)

func (MAV_BATTERY_CHARGE_STATE) Bitmask

func (e MAV_BATTERY_CHARGE_STATE) Bitmask() string

Bitmask return string representetion of intersects MAV_BATTERY_CHARGE_STATE enums

func (MAV_BATTERY_CHARGE_STATE) MarshalBinary

func (e MAV_BATTERY_CHARGE_STATE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_BATTERY_CHARGE_STATE) String

func (e MAV_BATTERY_CHARGE_STATE) String() string

func (*MAV_BATTERY_CHARGE_STATE) UnmarshalBinary

func (e *MAV_BATTERY_CHARGE_STATE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_BATTERY_FAULT

type MAV_BATTERY_FAULT int

MAV_BATTERY_FAULT type. Smart battery supply status/fault flags (bitmask) for health indication. The battery must also report either MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY if any of these are set.

const (
	// MAV_BATTERY_FAULT_DEEP_DISCHARGE enum. Battery has deep discharged
	MAV_BATTERY_FAULT_DEEP_DISCHARGE MAV_BATTERY_FAULT = 1
	// MAV_BATTERY_FAULT_SPIKES enum. Voltage spikes
	MAV_BATTERY_FAULT_SPIKES MAV_BATTERY_FAULT = 2
	// MAV_BATTERY_FAULT_CELL_FAIL enum. One or more cells have failed. Battery should also report MAV_BATTERY_CHARGE_STATE_FAILE (and should not be used)
	MAV_BATTERY_FAULT_CELL_FAIL MAV_BATTERY_FAULT = 4
	// MAV_BATTERY_FAULT_OVER_CURRENT enum. Over-current fault
	MAV_BATTERY_FAULT_OVER_CURRENT MAV_BATTERY_FAULT = 8
	// MAV_BATTERY_FAULT_OVER_TEMPERATURE enum. Over-temperature fault
	MAV_BATTERY_FAULT_OVER_TEMPERATURE MAV_BATTERY_FAULT = 16
	// MAV_BATTERY_FAULT_UNDER_TEMPERATURE enum. Under-temperature fault
	MAV_BATTERY_FAULT_UNDER_TEMPERATURE MAV_BATTERY_FAULT = 32
	// MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE enum. Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage)
	MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE MAV_BATTERY_FAULT = 64
)

func (MAV_BATTERY_FAULT) Bitmask

func (e MAV_BATTERY_FAULT) Bitmask() string

Bitmask return string representetion of intersects MAV_BATTERY_FAULT enums

func (MAV_BATTERY_FAULT) MarshalBinary

func (e MAV_BATTERY_FAULT) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_BATTERY_FAULT) String

func (e MAV_BATTERY_FAULT) String() string

func (*MAV_BATTERY_FAULT) UnmarshalBinary

func (e *MAV_BATTERY_FAULT) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_BATTERY_FUNCTION

type MAV_BATTERY_FUNCTION int

MAV_BATTERY_FUNCTION type. Enumeration of battery functions

const (
	// MAV_BATTERY_FUNCTION_UNKNOWN enum. Battery function is unknown
	MAV_BATTERY_FUNCTION_UNKNOWN MAV_BATTERY_FUNCTION = 0
	// MAV_BATTERY_FUNCTION_ALL enum. Battery supports all flight systems
	MAV_BATTERY_FUNCTION_ALL MAV_BATTERY_FUNCTION = 1
	// MAV_BATTERY_FUNCTION_PROPULSION enum. Battery for the propulsion system
	MAV_BATTERY_FUNCTION_PROPULSION MAV_BATTERY_FUNCTION = 2
	// MAV_BATTERY_FUNCTION_AVIONICS enum. Avionics battery
	MAV_BATTERY_FUNCTION_AVIONICS MAV_BATTERY_FUNCTION = 3
	// MAV_BATTERY_TYPE_PAYLOAD enum. Payload battery
	MAV_BATTERY_TYPE_PAYLOAD MAV_BATTERY_FUNCTION = 4
)

func (MAV_BATTERY_FUNCTION) Bitmask

func (e MAV_BATTERY_FUNCTION) Bitmask() string

Bitmask return string representetion of intersects MAV_BATTERY_FUNCTION enums

func (MAV_BATTERY_FUNCTION) MarshalBinary

func (e MAV_BATTERY_FUNCTION) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_BATTERY_FUNCTION) String

func (e MAV_BATTERY_FUNCTION) String() string

func (*MAV_BATTERY_FUNCTION) UnmarshalBinary

func (e *MAV_BATTERY_FUNCTION) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_BATTERY_MODE

type MAV_BATTERY_MODE int

MAV_BATTERY_MODE type. Battery mode. Note, the normal operation mode (i.e. when flying) should be reported as MAV_BATTERY_MODE_UNKNOWN to allow message trimming in normal flight.

const (
	// MAV_BATTERY_MODE_UNKNOWN enum. Battery mode not supported/unknown battery mode/normal operation
	MAV_BATTERY_MODE_UNKNOWN MAV_BATTERY_MODE = 0
	// MAV_BATTERY_MODE_AUTO_DISCHARGING enum. Battery is auto discharging (towards storage level)
	MAV_BATTERY_MODE_AUTO_DISCHARGING MAV_BATTERY_MODE = 1
	// MAV_BATTERY_MODE_HOT_SWAP enum. Battery in hot-swap mode (current limited to prevent spikes that might damage sensitive electrical circuits)
	MAV_BATTERY_MODE_HOT_SWAP MAV_BATTERY_MODE = 2
)

func (MAV_BATTERY_MODE) Bitmask

func (e MAV_BATTERY_MODE) Bitmask() string

Bitmask return string representetion of intersects MAV_BATTERY_MODE enums

func (MAV_BATTERY_MODE) MarshalBinary

func (e MAV_BATTERY_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_BATTERY_MODE) String

func (e MAV_BATTERY_MODE) String() string

func (*MAV_BATTERY_MODE) UnmarshalBinary

func (e *MAV_BATTERY_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_BATTERY_TYPE

type MAV_BATTERY_TYPE int

MAV_BATTERY_TYPE type. Enumeration of battery types

const (
	// MAV_BATTERY_TYPE_UNKNOWN enum. Not specified
	MAV_BATTERY_TYPE_UNKNOWN MAV_BATTERY_TYPE = 0
	// MAV_BATTERY_TYPE_LIPO enum. Lithium polymer battery
	MAV_BATTERY_TYPE_LIPO MAV_BATTERY_TYPE = 1
	// MAV_BATTERY_TYPE_LIFE enum. Lithium-iron-phosphate battery
	MAV_BATTERY_TYPE_LIFE MAV_BATTERY_TYPE = 2
	// MAV_BATTERY_TYPE_LION enum. Lithium-ION battery
	MAV_BATTERY_TYPE_LION MAV_BATTERY_TYPE = 3
	// MAV_BATTERY_TYPE_NIMH enum. Nickel metal hydride battery
	MAV_BATTERY_TYPE_NIMH MAV_BATTERY_TYPE = 4
)

func (MAV_BATTERY_TYPE) Bitmask

func (e MAV_BATTERY_TYPE) Bitmask() string

Bitmask return string representetion of intersects MAV_BATTERY_TYPE enums

func (MAV_BATTERY_TYPE) MarshalBinary

func (e MAV_BATTERY_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_BATTERY_TYPE) String

func (e MAV_BATTERY_TYPE) String() string

func (*MAV_BATTERY_TYPE) UnmarshalBinary

func (e *MAV_BATTERY_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_CMD

type MAV_CMD int

MAV_CMD type

const (
	// MAV_CMD_DO_SET_RESUME_REPEAT_DIST enum. Set the distance to be repeated on mission resume. Params: 1) Distance.; 2) Empty.; 3) Empty.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_DO_SET_RESUME_REPEAT_DIST MAV_CMD = 215
	// MAV_CMD_DO_SPRAYER enum. Control attached liquid sprayer. Params: 1) 0: disable sprayer. 1: enable sprayer.; 2) Empty.; 3) Empty.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_DO_SPRAYER MAV_CMD = 216
	// MAV_CMD_NAV_ALTITUDE_WAIT enum. Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up. Params: 1) Altitude.; 2) Descent speed.; 3) How long to wiggle the control surfaces to prevent them seizing up.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_NAV_ALTITUDE_WAIT MAV_CMD = 83
	// MAV_CMD_POWER_OFF_INITIATED enum. A system wide power-off event has been initiated. Params: 1) Empty.; 2) Empty.; 3) Empty.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_POWER_OFF_INITIATED MAV_CMD = 42000
	// MAV_CMD_SOLO_BTN_FLY_CLICK enum. FLY button has been clicked. Params: 1) Empty.; 2) Empty.; 3) Empty.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_SOLO_BTN_FLY_CLICK MAV_CMD = 42001
	// MAV_CMD_SOLO_BTN_FLY_HOLD enum. FLY button has been held for 1.5 seconds. Params: 1) Takeoff altitude.; 2) Empty.; 3) Empty.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_SOLO_BTN_FLY_HOLD MAV_CMD = 42002
	// MAV_CMD_SOLO_BTN_PAUSE_CLICK enum. PAUSE button has been clicked. Params: 1) 1 if Solo is in a shot mode, 0 otherwise.; 2) Empty.; 3) Empty.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_SOLO_BTN_PAUSE_CLICK MAV_CMD = 42003
	// MAV_CMD_FIXED_MAG_CAL enum. Magnetometer calibration based on fixed position         in earth field given by inclination, declination and intensity. Params: 1) Magnetic declination.; 2) Magnetic inclination.; 3) Magnetic intensity.; 4) Yaw.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_FIXED_MAG_CAL MAV_CMD = 42004
	// MAV_CMD_FIXED_MAG_CAL_FIELD enum. Magnetometer calibration based on fixed expected field values. Params: 1) Field strength X.; 2) Field strength Y.; 3) Field strength Z.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_FIXED_MAG_CAL_FIELD MAV_CMD = 42005
	// MAV_CMD_DO_START_MAG_CAL enum. Initiate a magnetometer calibration. Params: 1) Bitmask of magnetometers to calibrate. Use 0 to calibrate all sensors that can be started (sensors may not start if disabled, unhealthy, etc.). The command will NACK if calibration does not start for a sensor explicitly specified by the bitmask.; 2) Automatically retry on failure (0=no retry, 1=retry).; 3) Save without user input (0=require input, 1=autosave).; 4) Delay.; 5) Autoreboot (0=user reboot, 1=autoreboot).; 6) Empty.; 7) Empty.;
	MAV_CMD_DO_START_MAG_CAL MAV_CMD = 42424
	// MAV_CMD_DO_ACCEPT_MAG_CAL enum. Accept a magnetometer calibration. Params: 1) Bitmask of magnetometers that calibration is accepted (0 means all).; 2) Empty.; 3) Empty.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_DO_ACCEPT_MAG_CAL MAV_CMD = 42425
	// MAV_CMD_DO_CANCEL_MAG_CAL enum. Cancel a running magnetometer calibration. Params: 1) Bitmask of magnetometers to cancel a running calibration (0 means all).; 2) Empty.; 3) Empty.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_DO_CANCEL_MAG_CAL MAV_CMD = 42426
	// MAV_CMD_ACCELCAL_VEHICLE_POS enum. Used when doing accelerometer calibration. When sent to the GCS tells it what position to put the vehicle in. When sent to the vehicle says what position the vehicle is in. Params: 1) Position.; 2) Empty.; 3) Empty.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_ACCELCAL_VEHICLE_POS MAV_CMD = 42429
	// MAV_CMD_DO_SEND_BANNER enum. Reply with the version banner. Params: 1) Empty.; 2) Empty.; 3) Empty.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_DO_SEND_BANNER MAV_CMD = 42428
	// MAV_CMD_SET_FACTORY_TEST_MODE enum. Command autopilot to get into factory test/diagnostic mode. Params: 1) 0: activate test mode, 1: exit test mode.; 2) Empty.; 3) Empty.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_SET_FACTORY_TEST_MODE MAV_CMD = 42427
	// MAV_CMD_GIMBAL_RESET enum. Causes the gimbal to reset and boot as if it was just powered on. Params: 1) Empty.; 2) Empty.; 3) Empty.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_GIMBAL_RESET MAV_CMD = 42501
	// MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS enum. Reports progress and success or failure of gimbal axis calibration procedure. Params: 1) Gimbal axis we're reporting calibration progress for.; 2) Current calibration progress for this axis.; 3) Status of the calibration.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS MAV_CMD = 42502
	// MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION enum. Starts commutation calibration on the gimbal. Params: 1) Empty.; 2) Empty.; 3) Empty.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION MAV_CMD = 42503
	// MAV_CMD_GIMBAL_FULL_RESET enum. Erases gimbal application and parameters. Params: 1) Magic number.; 2) Magic number.; 3) Magic number.; 4) Magic number.; 5) Magic number.; 6) Magic number.; 7) Magic number.;
	MAV_CMD_GIMBAL_FULL_RESET MAV_CMD = 42505
	// MAV_CMD_FLASH_BOOTLOADER enum. Update the bootloader. Params: 1) Empty; 2) Empty; 3) Empty; 4) Empty; 5) Magic number - set to 290876 to actually flash; 6) Empty; 7) Empty;
	MAV_CMD_FLASH_BOOTLOADER MAV_CMD = 42650
	// MAV_CMD_BATTERY_RESET enum. Reset battery capacity for batteries that accumulate consumed battery via integration. Params: 1) Bitmask of batteries to reset. Least significant bit is for the first battery.; 2) Battery percentage remaining to set.;
	MAV_CMD_BATTERY_RESET MAV_CMD = 42651
	// MAV_CMD_DEBUG_TRAP enum. Issue a trap signal to the autopilot process, presumably to enter the debugger. Params: 1) Magic number - set to 32451 to actually trap.; 2) Empty.; 3) Empty.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_DEBUG_TRAP MAV_CMD = 42700
	// MAV_CMD_SCRIPTING enum. Control onboard scripting. Params: 1) Scripting command to execute;
	MAV_CMD_SCRIPTING MAV_CMD = 42701
	// MAV_CMD_GUIDED_CHANGE_SPEED enum. Change flight speed at a given rate. This slews the vehicle at a controllable rate between it's previous speed and the new one. (affects GUIDED only. Outside GUIDED, aircraft ignores these commands. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.). Params: 1) Airspeed or groundspeed.; 2) Target Speed; 3) Acceleration rate, 0 to take effect instantly; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_GUIDED_CHANGE_SPEED MAV_CMD = 43000
	// MAV_CMD_GUIDED_CHANGE_ALTITUDE enum. Change target altitude at a given rate. This slews the vehicle at a controllable rate between it's previous altitude and the new one. (affects GUIDED only. Outside GUIDED, aircraft ignores these commands. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.). Params: 1) Empty; 2) Empty; 3) Rate of change, toward new altitude. 0 for maximum rate change. Positive numbers only, as negative numbers will not converge on the new target alt.; 4) Empty; 5) Empty; 6) Empty; 7) Target Altitude;
	MAV_CMD_GUIDED_CHANGE_ALTITUDE MAV_CMD = 43001
	// MAV_CMD_GUIDED_CHANGE_HEADING enum. Change to target heading at a given rate, overriding previous heading/s. This slews the vehicle at a controllable rate between it's previous heading and the new one. (affects GUIDED only. Exiting GUIDED returns aircraft to normal behaviour defined elsewhere. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.). Params: 1) course-over-ground or raw vehicle heading.; 2) Target heading.; 3) Maximum centripetal accelearation, ie rate of change,  toward new heading.; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_GUIDED_CHANGE_HEADING MAV_CMD = 43002
	// MAV_CMD_NAV_WAYPOINT enum. Navigate to waypoint. Params: 1) Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing); 2) Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached); 3) 0 to pass through the WP, if > 0 radius to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.; 4) Desired yaw angle at waypoint (rotary wing). NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).; 5) Latitude; 6) Longitude; 7) Altitude;
	MAV_CMD_NAV_WAYPOINT MAV_CMD = 16
	// MAV_CMD_NAV_LOITER_UNLIM enum. Loiter around this waypoint an unlimited amount of time. Params: 1) Empty; 2) Empty; 3) Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise; 4) Desired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).; 5) Latitude; 6) Longitude; 7) Altitude;
	MAV_CMD_NAV_LOITER_UNLIM MAV_CMD = 17
	// MAV_CMD_NAV_LOITER_TURNS enum. Loiter around this waypoint for X turns. Params: 1) Number of turns.; 2) Leave loiter circle only once heading towards the next waypoint (0 = False); 3) Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise; 4) Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.; 5) Latitude; 6) Longitude; 7) Altitude;
	MAV_CMD_NAV_LOITER_TURNS MAV_CMD = 18
	// MAV_CMD_NAV_LOITER_TIME enum. Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint. Params: 1) Loiter time (only starts once Lat, Lon and Alt is reached).; 2) Leave loiter circle only once heading towards the next waypoint (0 = False); 3) Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise.; 4) Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.; 5) Latitude; 6) Longitude; 7) Altitude;
	MAV_CMD_NAV_LOITER_TIME MAV_CMD = 19
	// MAV_CMD_NAV_RETURN_TO_LAUNCH enum. Return to launch location. Params: 1) Empty; 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_NAV_RETURN_TO_LAUNCH MAV_CMD = 20
	// MAV_CMD_NAV_LAND enum. Land at location. Params: 1) Minimum target altitude if landing is aborted (0 = undefined/use system default).; 2) Precision land mode.; 3) Empty.; 4) Desired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).; 5) Latitude.; 6) Longitude.; 7) Landing altitude (ground level in current frame).;
	MAV_CMD_NAV_LAND MAV_CMD = 21
	// MAV_CMD_NAV_TAKEOFF enum. Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode. Params: 1) Minimum pitch (if airspeed sensor present), desired pitch without sensor; 2) Empty; 3) Empty; 4) Yaw angle (if magnetometer present), ignored without magnetometer. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).; 5) Latitude; 6) Longitude; 7) Altitude;
	MAV_CMD_NAV_TAKEOFF MAV_CMD = 22
	// MAV_CMD_NAV_LAND_LOCAL enum. Land at local position (local frame only). Params: 1) Landing target number (if available); 2) Maximum accepted offset from desired landing position - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land; 3) Landing descend rate; 4) Desired yaw angle; 5) Y-axis position; 6) X-axis position; 7) Z-axis / ground level position;
	MAV_CMD_NAV_LAND_LOCAL MAV_CMD = 23
	// MAV_CMD_NAV_TAKEOFF_LOCAL enum. Takeoff from local position (local frame only). Params: 1) Minimum pitch (if airspeed sensor present), desired pitch without sensor; 2) Empty; 3) Takeoff ascend rate; 4) Yaw angle (if magnetometer or another yaw estimation source present), ignored without one of these; 5) Y-axis position; 6) X-axis position; 7) Z-axis position;
	MAV_CMD_NAV_TAKEOFF_LOCAL MAV_CMD = 24
	// MAV_CMD_NAV_FOLLOW enum. Vehicle following, i.e. this waypoint represents the position of a moving vehicle. Params: 1) Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation; 2) Ground speed of vehicle to be followed; 3) Radius around waypoint. If positive loiter clockwise, else counter-clockwise; 4) Desired yaw angle.; 5) Latitude; 6) Longitude; 7) Altitude;
	MAV_CMD_NAV_FOLLOW MAV_CMD = 25
	// MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT enum. 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. Params: 1) Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude.; 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Desired altitude;
	MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT MAV_CMD = 30
	// MAV_CMD_NAV_LOITER_TO_ALT enum. 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. Params: 1) Leave loiter circle only once heading towards the next waypoint (0 = False); 2) Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.; 3) Empty; 4) Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.; 5) Latitude; 6) Longitude; 7) Altitude;
	MAV_CMD_NAV_LOITER_TO_ALT MAV_CMD = 31
	// MAV_CMD_DO_FOLLOW enum. Begin following a target. Params: 1) System ID (of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode.; 2) Reserved; 3) Reserved; 4) Altitude mode: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home.; 5) Altitude above home. (used if mode=2); 6) Reserved; 7) Time to land in which the MAV should go to the default position hold mode after a message RX timeout.;
	MAV_CMD_DO_FOLLOW MAV_CMD = 32
	// MAV_CMD_DO_FOLLOW_REPOSITION enum. Reposition the MAV after a follow target command has been sent. Params: 1) Camera q1 (where 0 is on the ray from the camera to the tracking device); 2) Camera q2; 3) Camera q3; 4) Camera q4; 5) altitude offset from target; 6) X offset from target; 7) Y offset from target;
	MAV_CMD_DO_FOLLOW_REPOSITION MAV_CMD = 33
	// MAV_CMD_DO_ORBIT enum. Start orbiting on the circumference of a circle defined by the parameters. Setting any value NaN results in using defaults. Params: 1) Radius of the circle. positive: Orbit clockwise. negative: Orbit counter-clockwise.; 2) Tangential Velocity. NaN: Vehicle configuration default.; 3) Yaw behavior of the vehicle.; 4) Reserved (e.g. for dynamic center beacon options); 5) Center point latitude (if no MAV_FRAME specified) / X coordinate according to MAV_FRAME. NaN: Use current vehicle position or current center if already orbiting.; 6) Center point longitude (if no MAV_FRAME specified) / Y coordinate according to MAV_FRAME. NaN: Use current vehicle position or current center if already orbiting.; 7) Center point altitude (MSL) (if no MAV_FRAME specified) / Z coordinate according to MAV_FRAME. NaN: Use current vehicle position or current center if already orbiting.;
	MAV_CMD_DO_ORBIT MAV_CMD = 34
	// MAV_CMD_NAV_ROI enum. Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. Params: 1) Region of interest mode.; 2) Waypoint index/ target ID. (see MAV_ROI enum); 3) ROI index (allows a vehicle to manage multiple ROI's); 4) Empty; 5) x the location of the fixed ROI (see MAV_FRAME); 6) y; 7) z;
	MAV_CMD_NAV_ROI MAV_CMD = 80
	// MAV_CMD_NAV_PATHPLANNING enum. Control autonomous path planning on the MAV. Params: 1) 0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning; 2) 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid; 3) Empty; 4) Yaw angle at goal; 5) Latitude/X of goal; 6) Longitude/Y of goal; 7) Altitude/Z of goal;
	MAV_CMD_NAV_PATHPLANNING MAV_CMD = 81
	// MAV_CMD_NAV_SPLINE_WAYPOINT enum. Navigate to waypoint using a spline path. Params: 1) Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing); 2) Empty; 3) Empty; 4) Empty; 5) Latitude/X of goal; 6) Longitude/Y of goal; 7) Altitude/Z of goal;
	MAV_CMD_NAV_SPLINE_WAYPOINT MAV_CMD = 82
	// MAV_CMD_NAV_VTOL_TAKEOFF enum. Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.). Params: 1) Empty; 2) Front transition heading.; 3) Empty; 4) Yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).; 5) Latitude; 6) Longitude; 7) Altitude;
	MAV_CMD_NAV_VTOL_TAKEOFF MAV_CMD = 84
	// MAV_CMD_NAV_VTOL_LAND enum. Land using VTOL mode. Params: 1) Empty; 2) Empty; 3) Approach altitude (with the same reference as the Altitude field). NaN if unspecified.; 4) Yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).; 5) Latitude; 6) Longitude; 7) Altitude (ground level);
	MAV_CMD_NAV_VTOL_LAND MAV_CMD = 85
	// MAV_CMD_NAV_GUIDED_ENABLE enum. hand control over to an external controller. Params: 1) On / Off (> 0.5f on); 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_NAV_GUIDED_ENABLE MAV_CMD = 92
	// MAV_CMD_NAV_DELAY enum. Delay the next navigation command a number of seconds or until a specified time. Params: 1) Delay (-1 to enable time-of-day fields); 2) hour (24h format, UTC, -1 to ignore); 3) minute (24h format, UTC, -1 to ignore); 4) second (24h format, UTC, -1 to ignore); 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_NAV_DELAY MAV_CMD = 93
	// MAV_CMD_NAV_PAYLOAD_PLACE enum. 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. Params: 1) Maximum distance to descend.; 2) Empty; 3) Empty; 4) Empty; 5) Latitude; 6) Longitude; 7) Altitude;
	MAV_CMD_NAV_PAYLOAD_PLACE MAV_CMD = 94
	// MAV_CMD_NAV_LAST enum. NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration. Params: 1) Empty; 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_NAV_LAST MAV_CMD = 95
	// MAV_CMD_CONDITION_DELAY enum. Delay mission state machine. Params: 1) Delay; 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_CONDITION_DELAY MAV_CMD = 112
	// MAV_CMD_CONDITION_CHANGE_ALT enum. Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached. Params: 1) Descent / Ascend rate.; 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Target Altitude;
	MAV_CMD_CONDITION_CHANGE_ALT MAV_CMD = 113
	// MAV_CMD_CONDITION_DISTANCE enum. Delay mission state machine until within desired distance of next NAV point. Params: 1) Distance.; 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_CONDITION_DISTANCE MAV_CMD = 114
	// MAV_CMD_CONDITION_YAW enum. Reach a certain target angle. Params: 1) target angle, 0 is north; 2) angular speed; 3) direction: -1: counter clockwise, 1: clockwise; 4) 0: absolute angle, 1: relative offset; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_CONDITION_YAW MAV_CMD = 115
	// MAV_CMD_CONDITION_LAST enum. NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration. Params: 1) Empty; 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_CONDITION_LAST MAV_CMD = 159
	// MAV_CMD_DO_SET_MODE enum. Set system mode. Params: 1) Mode; 2) Custom mode - this is system specific, please refer to the individual autopilot specifications for details.; 3) Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_SET_MODE MAV_CMD = 176
	// MAV_CMD_DO_JUMP enum. Jump to the desired command in the mission list.  Repeat this action only the specified number of times. Params: 1) Sequence number; 2) Repeat count; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_JUMP MAV_CMD = 177
	// MAV_CMD_DO_CHANGE_SPEED enum. Change speed and/or throttle set points. Params: 1) Speed type (0=Airspeed, 1=Ground Speed, 2=Climb Speed, 3=Descent Speed); 2) Speed (-1 indicates no change); 3) Throttle (-1 indicates no change); 4) 0: absolute, 1: relative; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_CHANGE_SPEED MAV_CMD = 178
	// MAV_CMD_DO_SET_HOME enum. Changes the home location either to the current location or a specified location. Params: 1) Use current (1=use current location, 0=use specified location); 2) Empty; 3) Empty; 4) Yaw angle. NaN to use default heading; 5) Latitude; 6) Longitude; 7) Altitude;
	MAV_CMD_DO_SET_HOME MAV_CMD = 179
	// MAV_CMD_DO_SET_PARAMETER enum. Set a system parameter.  Caution!  Use of this command requires knowledge of the numeric enumeration value of the parameter. Params: 1) Parameter number; 2) Parameter value; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_SET_PARAMETER MAV_CMD = 180
	// MAV_CMD_DO_SET_RELAY enum. Set a relay to a condition. Params: 1) Relay instance number.; 2) Setting. (1=on, 0=off, others possible depending on system hardware); 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_SET_RELAY MAV_CMD = 181
	// MAV_CMD_DO_REPEAT_RELAY enum. Cycle a relay on and off for a desired number of cycles with a desired period. Params: 1) Relay instance number.; 2) Cycle count.; 3) Cycle time.; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_REPEAT_RELAY MAV_CMD = 182
	// MAV_CMD_DO_SET_SERVO enum. Set a servo to a desired PWM value. Params: 1) Servo instance number.; 2) Pulse Width Modulation.; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_SET_SERVO MAV_CMD = 183
	// MAV_CMD_DO_REPEAT_SERVO enum. Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. Params: 1) Servo instance number.; 2) Pulse Width Modulation.; 3) Cycle count.; 4) Cycle time.; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_REPEAT_SERVO MAV_CMD = 184
	// MAV_CMD_DO_FLIGHTTERMINATION enum. Terminate flight immediately. Params: 1) Flight termination activated if > 0.5; 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_FLIGHTTERMINATION MAV_CMD = 185
	// MAV_CMD_DO_CHANGE_ALTITUDE enum. Change altitude set point. Params: 1) Altitude.; 2) Frame of new altitude.; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_CHANGE_ALTITUDE MAV_CMD = 186
	// MAV_CMD_DO_SET_ACTUATOR enum. Sets actuators (e.g. servos) to a desired value. The actuator numbers are mapped to specific outputs (e.g. on any MAIN or AUX PWM or UAVCAN) using a flight-stack specific mechanism (i.e. a parameter). Params: 1) Actuator 1 value, scaled from [-1 to 1]. NaN to ignore.; 2) Actuator 2 value, scaled from [-1 to 1]. NaN to ignore.; 3) Actuator 3 value, scaled from [-1 to 1]. NaN to ignore.; 4) Actuator 4 value, scaled from [-1 to 1]. NaN to ignore.; 5) Actuator 5 value, scaled from [-1 to 1]. NaN to ignore.; 6) Actuator 6 value, scaled from [-1 to 1]. NaN to ignore.; 7) Index of actuator set (i.e if set to 1, Actuator 1 becomes Actuator 7);
	MAV_CMD_DO_SET_ACTUATOR MAV_CMD = 187
	// MAV_CMD_DO_LAND_START enum. 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. Params: 1) Empty; 2) Empty; 3) Empty; 4) Empty; 5) Latitude; 6) Longitude; 7) Empty;
	MAV_CMD_DO_LAND_START MAV_CMD = 189
	// MAV_CMD_DO_RALLY_LAND enum. Mission command to perform a landing from a rally point. Params: 1) Break altitude; 2) Landing speed; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_RALLY_LAND MAV_CMD = 190
	// MAV_CMD_DO_GO_AROUND enum. Mission command to safely abort an autonomous landing. Params: 1) Altitude; 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_GO_AROUND MAV_CMD = 191
	// MAV_CMD_DO_REPOSITION enum. Reposition the vehicle to a specific WGS84 global position. Params: 1) Ground speed, less than 0 (-1) for default; 2) Bitmask of option flags.; 3) Reserved; 4) Yaw heading. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). For planes indicates loiter direction (0: clockwise, 1: counter clockwise); 5) Latitude; 6) Longitude; 7) Altitude;
	MAV_CMD_DO_REPOSITION MAV_CMD = 192
	// MAV_CMD_DO_PAUSE_CONTINUE enum. If in a GPS controlled position mode, hold the current position or continue. Params: 1) 0: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.; 2) Reserved; 3) Reserved; 4) Reserved; 5) Reserved; 6) Reserved; 7) Reserved;
	MAV_CMD_DO_PAUSE_CONTINUE MAV_CMD = 193
	// MAV_CMD_DO_SET_REVERSE enum. Set moving direction to forward or reverse. Params: 1) Direction (0=Forward, 1=Reverse); 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_SET_REVERSE MAV_CMD = 194
	// MAV_CMD_DO_SET_ROI_LOCATION enum. Sets the region of interest (ROI) to a location. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal is not to react to this message. Params: 1) Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).; 2) Empty; 3) Empty; 4) Empty; 5) Latitude of ROI location; 6) Longitude of ROI location; 7) Altitude of ROI location;
	MAV_CMD_DO_SET_ROI_LOCATION MAV_CMD = 195
	// MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET enum. Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. Params: 1) Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).; 2) Empty; 3) Empty; 4) Empty; 5) Pitch offset from next waypoint, positive pitching up; 6) Roll offset from next waypoint, positive rolling to the right; 7) Yaw offset from next waypoint, positive yawing to the right;
	MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET MAV_CMD = 196
	// MAV_CMD_DO_SET_ROI_NONE enum. Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. After this command the gimbal manager should go back to manual input if available, and otherwise assume a neutral position. Params: 1) Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).; 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_SET_ROI_NONE MAV_CMD = 197
	// MAV_CMD_DO_SET_ROI_SYSID enum. Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. Params: 1) System ID; 2) Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).;
	MAV_CMD_DO_SET_ROI_SYSID MAV_CMD = 198
	// MAV_CMD_DO_CONTROL_VIDEO enum. Control onboard camera system. Params: 1) Camera ID (-1 for all); 2) Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw; 3) Transmission mode: 0: video stream, >0: single images every n seconds; 4) Recording: 0: disabled, 1: enabled compressed, 2: enabled raw; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_CONTROL_VIDEO MAV_CMD = 200
	// MAV_CMD_DO_SET_ROI enum. Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. Params: 1) Region of interest mode.; 2) Waypoint index/ target ID (depends on param 1).; 3) Region of interest index. (allows a vehicle to manage multiple ROI's); 4) Empty; 5) MAV_ROI_WPNEXT: pitch offset from next waypoint, MAV_ROI_LOCATION: latitude; 6) MAV_ROI_WPNEXT: roll offset from next waypoint, MAV_ROI_LOCATION: longitude; 7) MAV_ROI_WPNEXT: yaw offset from next waypoint, MAV_ROI_LOCATION: altitude;
	MAV_CMD_DO_SET_ROI MAV_CMD = 201
	// MAV_CMD_DO_DIGICAM_CONFIGURE enum. 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 ). Params: 1) Modes: P, TV, AV, M, Etc.; 2) Shutter speed: Divisor number for one second.; 3) Aperture: F stop number.; 4) ISO number e.g. 80, 100, 200, Etc.; 5) Exposure type enumerator.; 6) Command Identity.; 7) Main engine cut-off time before camera trigger. (0 means no cut-off);
	MAV_CMD_DO_DIGICAM_CONFIGURE MAV_CMD = 202
	// MAV_CMD_DO_DIGICAM_CONTROL enum. 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 ). Params: 1) Session control e.g. show/hide lens; 2) Zoom's absolute position; 3) Zooming step value to offset zoom from the current position; 4) Focus Locking, Unlocking or Re-locking; 5) Shooting Command; 6) Command Identity; 7) Test shot identifier. If set to 1, image will only be captured, but not counted towards internal frame count.;
	MAV_CMD_DO_DIGICAM_CONTROL MAV_CMD = 203
	// MAV_CMD_DO_MOUNT_CONFIGURE enum. Mission command to configure a camera or antenna mount. Params: 1) Mount operation mode; 2) stabilize roll? (1 = yes, 0 = no); 3) stabilize pitch? (1 = yes, 0 = no); 4) stabilize yaw? (1 = yes, 0 = no); 5) roll input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame); 6) pitch input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame); 7) yaw input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame);
	MAV_CMD_DO_MOUNT_CONFIGURE MAV_CMD = 204
	// MAV_CMD_DO_MOUNT_CONTROL enum. Mission command to control a camera or antenna mount. Params: 1) pitch depending on mount mode (degrees or degrees/second depending on pitch input).; 2) roll depending on mount mode (degrees or degrees/second depending on roll input).; 3) yaw depending on mount mode (degrees or degrees/second depending on yaw input).; 4) altitude depending on mount mode.; 5) latitude, set if appropriate mount mode.; 6) longitude, set if appropriate mount mode.; 7) Mount mode.;
	MAV_CMD_DO_MOUNT_CONTROL MAV_CMD = 205
	// MAV_CMD_DO_SET_CAM_TRIGG_DIST enum. 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. Params: 1) Camera trigger distance. 0 to stop triggering.; 2) Camera shutter integration time. -1 or 0 to ignore; 3) Trigger camera once immediately. (0 = no trigger, 1 = trigger); 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_SET_CAM_TRIGG_DIST MAV_CMD = 206
	// MAV_CMD_DO_FENCE_ENABLE enum. Mission command to enable the geofence. Params: 1) enable? (0=disable, 1=enable, 2=disable_floor_only); 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_FENCE_ENABLE MAV_CMD = 207
	// MAV_CMD_DO_PARACHUTE enum. Mission item/command to release a parachute or enable/disable auto release. Params: 1) Action; 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_PARACHUTE MAV_CMD = 208
	// MAV_CMD_DO_MOTOR_TEST enum. Mission command to perform motor test. Params: 1) Motor instance number. (from 1 to max number of motors on the vehicle); 2) Throttle type.; 3) Throttle.; 4) Timeout.; 5) Motor count. (number of motors to test to test in sequence, waiting for the timeout above between them; 0=1 motor, 1=1 motor, 2=2 motors...); 6) Motor test order.; 7) Empty;
	MAV_CMD_DO_MOTOR_TEST MAV_CMD = 209
	// MAV_CMD_DO_INVERTED_FLIGHT enum. Change to/from inverted flight. Params: 1) Inverted flight. (0=normal, 1=inverted); 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_INVERTED_FLIGHT MAV_CMD = 210
	// MAV_CMD_DO_GRIPPER enum. Mission command to operate a gripper. Params: 1) Gripper instance number.; 2) Gripper action to perform.; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_GRIPPER MAV_CMD = 211
	// MAV_CMD_DO_AUTOTUNE_ENABLE enum. Enable/disable autotune. Params: 1) Enable (1: enable, 0:disable).; 2) Empty.; 3) Empty.; 4) Empty.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_DO_AUTOTUNE_ENABLE MAV_CMD = 212
	// MAV_CMD_NAV_SET_YAW_SPEED enum. Sets a desired vehicle turn angle and speed change. Params: 1) Yaw angle to adjust steering by.; 2) Speed.; 3) Final angle. (0=absolute, 1=relative); 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_NAV_SET_YAW_SPEED MAV_CMD = 213
	// MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL enum. 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. Params: 1) Camera trigger cycle time. -1 or 0 to ignore.; 2) Camera shutter integration time. Should be less than trigger cycle time. -1 or 0 to ignore.; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL MAV_CMD = 214
	// MAV_CMD_DO_MOUNT_CONTROL_QUAT enum. Mission command to control a camera or antenna mount, using a quaternion as reference. Params: 1) quaternion param q1, w (1 in null-rotation); 2) quaternion param q2, x (0 in null-rotation); 3) quaternion param q3, y (0 in null-rotation); 4) quaternion param q4, z (0 in null-rotation); 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_MOUNT_CONTROL_QUAT MAV_CMD = 220
	// MAV_CMD_DO_GUIDED_MASTER enum. set id of master controller. Params: 1) System ID; 2) Component ID; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_GUIDED_MASTER MAV_CMD = 221
	// MAV_CMD_DO_GUIDED_LIMITS enum. Set limits for external control. Params: 1) Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout.; 2) Altitude (MSL) min - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit.; 3) Altitude (MSL) max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit.; 4) Horizontal move limit - if vehicle moves more than this distance from its location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal move limit.; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_GUIDED_LIMITS MAV_CMD = 222
	// MAV_CMD_DO_ENGINE_CONTROL enum. 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. Params: 1) 0: Stop engine, 1:Start Engine; 2) 0: Warm start, 1:Cold start. Controls use of choke where applicable; 3) Height delay. This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay.; 4) Empty; 5) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_ENGINE_CONTROL MAV_CMD = 223
	// MAV_CMD_DO_SET_MISSION_CURRENT enum. 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). Params: 1) Mission sequence value to set; 2) Empty; 3) Empty; 4) Empty; 5) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_SET_MISSION_CURRENT MAV_CMD = 224
	// MAV_CMD_DO_LAST enum. NOP - This command is only used to mark the upper limit of the DO commands in the enumeration. Params: 1) Empty; 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_DO_LAST MAV_CMD = 240
	// MAV_CMD_PREFLIGHT_CALIBRATION enum. 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. Params: 1) 1: gyro calibration, 3: gyro temperature calibration; 2) 1: magnetometer calibration; 3) 1: ground pressure calibration; 4) 1: radio RC calibration, 2: RC trim calibration; 5) 1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration, 4: simple accelerometer calibration; 6) 1: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibration; 7) 1: ESC calibration, 3: barometer temperature calibration;
	MAV_CMD_PREFLIGHT_CALIBRATION MAV_CMD = 241
	// MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS enum. Set sensor offsets. This command will be only accepted if in pre-flight mode. Params: 1) Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer, 6: third magnetometer; 2) X axis offset (or generic dimension 1), in the sensor's raw units; 3) Y axis offset (or generic dimension 2), in the sensor's raw units; 4) Z axis offset (or generic dimension 3), in the sensor's raw units; 5) Generic dimension 4, in the sensor's raw units; 6) Generic dimension 5, in the sensor's raw units; 7) Generic dimension 6, in the sensor's raw units;
	MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS MAV_CMD = 242
	// MAV_CMD_PREFLIGHT_UAVCAN enum. Trigger UAVCAN configuration (actuator ID assignment and direction mapping). Note that this maps to the legacy UAVCAN v0 function UAVCAN_ENUMERATE, which is intended to be executed just once during initial vehicle configuration (it is not a normal pre-flight command and has been poorly named). Params: 1) 1: Trigger actuator ID assignment and direction mapping. 0: Cancel command.; 2) Reserved; 3) Reserved; 4) Reserved; 5) Reserved; 6) Reserved; 7) Reserved;
	MAV_CMD_PREFLIGHT_UAVCAN MAV_CMD = 243
	// MAV_CMD_PREFLIGHT_STORAGE enum. Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. Params: 1) Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults; 2) Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults; 3) Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: logging rate (e.g. set to 1000 for 1000 Hz logging); 4) Reserved; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_PREFLIGHT_STORAGE MAV_CMD = 245
	// MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN enum. Request the reboot or shutdown of system components. Params: 1) 0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.; 2) 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.; 3) WIP: 0: Do nothing for camera, 1: Reboot onboard camera, 2: Shutdown onboard camera, 3: Reboot onboard camera and keep it in the bootloader until upgraded; 4) WIP: 0: Do nothing for mount (e.g. gimbal), 1: Reboot mount, 2: Shutdown mount, 3: Reboot mount and keep it in the bootloader until upgraded; 5) Reserved (set to 0); 6) Reserved (set to 0); 7) WIP: ID (e.g. camera ID -1 for all IDs);
	MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN MAV_CMD = 246
	// MAV_CMD_DO_UPGRADE enum. Request a target system to start an upgrade of one (or all) of its components. For example, the command might be sent to a companion computer to cause it to upgrade a connected flight controller. The system doing the upgrade will report progress using the normal command protocol sequence for a long running operation. Command protocol information: https://mavlink.io/en/services/command.html. Params: 1) Component id of the component to be upgraded. If set to 0, all components should be upgraded.; 2) 0: Do not reboot component after the action is executed, 1: Reboot component after the action is executed.; 3) Reserved; 4) Reserved; 5) Reserved; 6) Reserved; 7) WIP: upgrade progress report rate (can be used for more granular control).;
	MAV_CMD_DO_UPGRADE MAV_CMD = 247
	// MAV_CMD_OVERRIDE_GOTO enum. 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. Params: 1) MAV_GOTO_DO_HOLD: pause mission and either hold or move to specified position (depending on param2), MAV_GOTO_DO_CONTINUE: resume mission.; 2) MAV_GOTO_HOLD_AT_CURRENT_POSITION: hold at current position, MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position.; 3) Coordinate frame of hold point.; 4) Desired yaw angle.; 5) Latitude/X position.; 6) Longitude/Y position.; 7) Altitude/Z position.;
	MAV_CMD_OVERRIDE_GOTO MAV_CMD = 252
	// MAV_CMD_OBLIQUE_SURVEY enum. Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera. Params: 1) Camera trigger distance. 0 to stop triggering.; 2) Camera shutter integration time. 0 to ignore; 3) The minimum interval in which the camera is capable of taking subsequent pictures repeatedly. 0 to ignore.; 4) Total number of roll positions at which the camera will capture photos (images captures spread evenly across the limits defined by param5).; 5) Angle limits that the camera can be rolled to left and right of center.; 6) Fixed pitch angle that the camera will hold in oblique mode if the mount is actuated in the pitch axis.; 7) Empty;
	MAV_CMD_OBLIQUE_SURVEY MAV_CMD = 260
	// MAV_CMD_MISSION_START enum. start running a mission. Params: 1) first_item: the first mission item to run; 2) last_item:  the last mission item to run (after this item is run, the mission ends);
	MAV_CMD_MISSION_START MAV_CMD = 300
	// MAV_CMD_COMPONENT_ARM_DISARM enum. Arms / Disarms a component. Params: 1) 0: disarm, 1: arm; 2) 0: arm-disarm unless prevented by safety checks (i.e. when landed), 21196: force arming/disarming (e.g. allow arming to override preflight checks and disarming in flight);
	MAV_CMD_COMPONENT_ARM_DISARM MAV_CMD = 400
	// MAV_CMD_ILLUMINATOR_ON_OFF enum. 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). Params: 1) 0: Illuminators OFF, 1: Illuminators ON;
	MAV_CMD_ILLUMINATOR_ON_OFF MAV_CMD = 405
	// MAV_CMD_GET_HOME_POSITION enum. Request the home position from the vehicle. Params: 1) Reserved; 2) Reserved; 3) Reserved; 4) Reserved; 5) Reserved; 6) Reserved; 7) Reserved;
	MAV_CMD_GET_HOME_POSITION MAV_CMD = 410
	// MAV_CMD_INJECT_FAILURE enum. Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting. Params: 1) The unit which is affected by the failure.; 2) The type how the failure manifests itself.; 3) Instance affected by failure (0 to signal all).;
	MAV_CMD_INJECT_FAILURE MAV_CMD = 420
	// MAV_CMD_START_RX_PAIR enum. Starts receiver pairing. Params: 1) 0:Spektrum.; 2) RC type.;
	MAV_CMD_START_RX_PAIR MAV_CMD = 500
	// MAV_CMD_GET_MESSAGE_INTERVAL enum. 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. Params: 1) The MAVLink message ID;
	MAV_CMD_GET_MESSAGE_INTERVAL MAV_CMD = 510
	// MAV_CMD_SET_MESSAGE_INTERVAL enum. Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM. Params: 1) The MAVLink message ID; 2) The interval between two messages. Set to -1 to disable and 0 to request default rate.; 7) Target address of message stream (if message has target address fields). 0: Flight-stack default (recommended), 1: address of requestor, 2: broadcast.;
	MAV_CMD_SET_MESSAGE_INTERVAL MAV_CMD = 511
	// MAV_CMD_REQUEST_MESSAGE enum. 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). Params: 1) The MAVLink message ID of the requested message.; 2) Use for index ID, if required. Otherwise, the use of this parameter (if any) must be defined in the requested message. By default assumed not used (0).; 3) The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).; 4) The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).; 5) The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).; 6) The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).; 7) Target address for requested message (if message has target address fields). 0: Flight-stack default, 1: address of requestor, 2: broadcast.;
	MAV_CMD_REQUEST_MESSAGE MAV_CMD = 512
	// MAV_CMD_REQUEST_PROTOCOL_VERSION enum. Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message. Params: 1) 1: Request supported protocol versions by all nodes on the network; 2) Reserved (all remaining params);
	MAV_CMD_REQUEST_PROTOCOL_VERSION MAV_CMD = 519
	// MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES enum. Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message. Params: 1) 1: Request autopilot version; 2) Reserved (all remaining params);
	MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES MAV_CMD = 520
	// MAV_CMD_REQUEST_CAMERA_INFORMATION enum. Request camera information (CAMERA_INFORMATION). Params: 1) 0: No action 1: Request camera capabilities; 2) Reserved (all remaining params);
	MAV_CMD_REQUEST_CAMERA_INFORMATION MAV_CMD = 521
	// MAV_CMD_REQUEST_CAMERA_SETTINGS enum. Request camera settings (CAMERA_SETTINGS). Params: 1) 0: No Action 1: Request camera settings; 2) Reserved (all remaining params);
	MAV_CMD_REQUEST_CAMERA_SETTINGS MAV_CMD = 522
	// MAV_CMD_REQUEST_STORAGE_INFORMATION enum. Request storage information (STORAGE_INFORMATION). Use the command's target_component to target a specific component's storage. Params: 1) Storage ID (0 for all, 1 for first, 2 for second, etc.); 2) 0: No Action 1: Request storage information; 3) Reserved (all remaining params);
	MAV_CMD_REQUEST_STORAGE_INFORMATION MAV_CMD = 525
	// MAV_CMD_STORAGE_FORMAT enum. 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. Params: 1) Storage ID (1 for first, 2 for second, etc.); 2) Format storage (and reset image log). 0: No action 1: Format storage; 3) Reset Image Log (without formatting storage medium). This will reset CAMERA_CAPTURE_STATUS.image_count and CAMERA_IMAGE_CAPTURED.image_index. 0: No action 1: Reset Image Log; 4) Reserved (all remaining params);
	MAV_CMD_STORAGE_FORMAT MAV_CMD = 526
	// MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS enum. Request camera capture status (CAMERA_CAPTURE_STATUS). Params: 1) 0: No Action 1: Request camera capture status; 2) Reserved (all remaining params);
	MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS MAV_CMD = 527
	// MAV_CMD_REQUEST_FLIGHT_INFORMATION enum. Request flight information (FLIGHT_INFORMATION). Params: 1) 1: Request flight information; 2) Reserved (all remaining params);
	MAV_CMD_REQUEST_FLIGHT_INFORMATION MAV_CMD = 528
	// MAV_CMD_RESET_CAMERA_SETTINGS enum. Reset all camera settings to Factory Default. Params: 1) 0: No Action 1: Reset all settings; 2) Reserved (all remaining params);
	MAV_CMD_RESET_CAMERA_SETTINGS MAV_CMD = 529
	// MAV_CMD_SET_CAMERA_MODE enum. 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. Params: 1) Reserved (Set to 0); 2) Camera mode; 3) ; 4) ; 7) ;
	MAV_CMD_SET_CAMERA_MODE MAV_CMD = 530
	// MAV_CMD_SET_CAMERA_ZOOM enum. Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success). Params: 1) Zoom type; 2) Zoom value. The range of valid values depend on the zoom type.; 3) ; 4) ; 7) ;
	MAV_CMD_SET_CAMERA_ZOOM MAV_CMD = 531
	// MAV_CMD_SET_CAMERA_FOCUS enum. Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success). Params: 1) Focus type; 2) Focus value; 3) ; 4) ; 7) ;
	MAV_CMD_SET_CAMERA_FOCUS MAV_CMD = 532
	// MAV_CMD_JUMP_TAG enum. Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG. Params: 1) Tag.;
	MAV_CMD_JUMP_TAG MAV_CMD = 600
	// MAV_CMD_DO_JUMP_TAG enum. 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. Params: 1) Target tag to jump to.; 2) Repeat count.;
	MAV_CMD_DO_JUMP_TAG MAV_CMD = 601
	// MAV_CMD_PARAM_TRANSACTION enum. Request to start or end a parameter transaction. Multiple kinds of transport layers can be used to exchange parameters in the transaction (param, param_ext and mavftp). The command response can either be a success/failure or an in progress in case the receiving side takes some time to apply the parameters. Params: 1) Action to be performed (start, commit, cancel, etc.); 2) Possible transport layers to set and get parameters via mavlink during a parameter transaction.; 3) Identifier for a specific transaction.;
	MAV_CMD_PARAM_TRANSACTION MAV_CMD = 900
	// MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW enum. High level setpoint to be sent to a gimbal manager to set a gimbal attitude. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: a gimbal is never to react to this command but only the gimbal manager. Params: 1) Pitch angle (positive to pitch up, relative to vehicle for FOLLOW mode, relative to world horizon for LOCK mode).; 2) Yaw angle (positive to yaw to the right, relative to vehicle for FOLLOW mode, absolute to North for LOCK mode).; 3) Pitch rate (positive to pitch up).; 4) Yaw rate (positive to yaw to the right).; 5) Gimbal manager flags to use.; 7) Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).;
	MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW MAV_CMD = 1000
	// MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE enum. Gimbal configuration to set which sysid/compid is in primary and secondary control. Params: 1) Sysid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).; 2) Compid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).; 3) Sysid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).; 4) Compid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).; 7) Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).;
	MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE MAV_CMD = 1001
	// MAV_CMD_IMAGE_START_CAPTURE enum. Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NaN for reserved values. Params: 1) Reserved (Set to 0); 2) Desired elapsed time between two consecutive pictures (in seconds). Minimum values depend on hardware (typically greater than 2 seconds).; 3) Total number of images to capture. 0 to capture forever/until MAV_CMD_IMAGE_STOP_CAPTURE.; 4) Capture sequence number starting from 1. This is only valid for single-capture (param3 == 1), otherwise set to 0. Increment the capture ID for each capture command to prevent double captures when a command is re-transmitted.; 5) ; 6) ; 7) ;
	MAV_CMD_IMAGE_START_CAPTURE MAV_CMD = 2000
	// MAV_CMD_IMAGE_STOP_CAPTURE enum. Stop image capture sequence Use NaN for reserved values. Params: 1) Reserved (Set to 0); 2) ; 3) ; 4) ; 7) ;
	MAV_CMD_IMAGE_STOP_CAPTURE MAV_CMD = 2001
	// MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE enum. Re-request a CAMERA_IMAGE_CAPTURED message. Params: 1) Sequence number for missing CAMERA_IMAGE_CAPTURED message; 2) ; 3) ; 4) ; 7) ;
	MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE MAV_CMD = 2002
	// MAV_CMD_DO_TRIGGER_CONTROL enum. Enable or disable on-board camera triggering system. Params: 1) Trigger enable/disable (0 for disable, 1 for start), -1 to ignore; 2) 1 to reset the trigger sequence, -1 or 0 to ignore; 3) 1 to pause triggering, but without switching the camera off or retracting it. -1 to ignore;
	MAV_CMD_DO_TRIGGER_CONTROL MAV_CMD = 2003
	// MAV_CMD_CAMERA_TRACK_POINT enum. If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking. Params: 1) Point to track x value (normalized 0..1, 0 is left, 1 is right).; 2) Point to track y value (normalized 0..1, 0 is top, 1 is bottom).; 3) Point radius (normalized 0..1, 0 is image left, 1 is image right).;
	MAV_CMD_CAMERA_TRACK_POINT MAV_CMD = 2004
	// MAV_CMD_CAMERA_TRACK_RECTANGLE enum. If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking. Params: 1) Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right).; 2) Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom).; 3) Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right).; 4) Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom).;
	MAV_CMD_CAMERA_TRACK_RECTANGLE MAV_CMD = 2005
	// MAV_CMD_CAMERA_STOP_TRACKING enum. Stops ongoing tracking
	MAV_CMD_CAMERA_STOP_TRACKING MAV_CMD = 2010
	// MAV_CMD_VIDEO_START_CAPTURE enum. Starts video capture (recording). Params: 1) Video Stream ID (0 for all streams); 2) Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise frequency); 3) ; 4) ; 5) ; 6) ; 7) ;
	MAV_CMD_VIDEO_START_CAPTURE MAV_CMD = 2500
	// MAV_CMD_VIDEO_STOP_CAPTURE enum. Stop the current video capture (recording). Params: 1) Video Stream ID (0 for all streams); 2) ; 3) ; 4) ; 5) ; 6) ; 7) ;
	MAV_CMD_VIDEO_STOP_CAPTURE MAV_CMD = 2501
	// MAV_CMD_VIDEO_START_STREAMING enum. Start video streaming. Params: 1) Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.);
	MAV_CMD_VIDEO_START_STREAMING MAV_CMD = 2502
	// MAV_CMD_VIDEO_STOP_STREAMING enum. Stop the given video stream. Params: 1) Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.);
	MAV_CMD_VIDEO_STOP_STREAMING MAV_CMD = 2503
	// MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION enum. Request video stream information (VIDEO_STREAM_INFORMATION). Params: 1) Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.);
	MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION MAV_CMD = 2504
	// MAV_CMD_REQUEST_VIDEO_STREAM_STATUS enum. Request video stream status (VIDEO_STREAM_STATUS). Params: 1) Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.);
	MAV_CMD_REQUEST_VIDEO_STREAM_STATUS MAV_CMD = 2505
	// MAV_CMD_LOGGING_START enum. Request to start streaming logging data over MAVLink (see also LOGGING_DATA message). Params: 1) Format: 0: ULog; 2) Reserved (set to 0); 3) Reserved (set to 0); 4) Reserved (set to 0); 5) Reserved (set to 0); 6) Reserved (set to 0); 7) Reserved (set to 0);
	MAV_CMD_LOGGING_START MAV_CMD = 2510
	// MAV_CMD_LOGGING_STOP enum. Request to stop streaming log data over MAVLink. Params: 1) Reserved (set to 0); 2) Reserved (set to 0); 3) Reserved (set to 0); 4) Reserved (set to 0); 5) Reserved (set to 0); 6) Reserved (set to 0); 7) Reserved (set to 0);
	MAV_CMD_LOGGING_STOP MAV_CMD = 2511
	// MAV_CMD_AIRFRAME_CONFIGURATION enum. Params: 1) Landing gear ID (default: 0, -1 for all); 2) Landing gear position (Down: 0, Up: 1, NaN for no change); 3) ; 4) ; 5) ; 6) ; 7) ;
	MAV_CMD_AIRFRAME_CONFIGURATION MAV_CMD = 2520
	// MAV_CMD_CONTROL_HIGH_LATENCY enum. Request to start/stop transmitting over the high latency telemetry. Params: 1) Control transmission over high latency telemetry (0: stop, 1: start); 2) Empty; 3) Empty; 4) Empty; 5) Empty; 6) Empty; 7) Empty;
	MAV_CMD_CONTROL_HIGH_LATENCY MAV_CMD = 2600
	// MAV_CMD_PANORAMA_CREATE enum. Create a panorama at the current position. Params: 1) Viewing angle horizontal of the panorama (+- 0.5 the total angle); 2) Viewing angle vertical of panorama.; 3) Speed of the horizontal rotation.; 4) Speed of the vertical rotation.;
	MAV_CMD_PANORAMA_CREATE MAV_CMD = 2800
	// MAV_CMD_DO_VTOL_TRANSITION enum. Request VTOL transition. Params: 1) The target VTOL state. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.;
	MAV_CMD_DO_VTOL_TRANSITION MAV_CMD = 3000
	// MAV_CMD_ARM_AUTHORIZATION_REQUEST enum. 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. Params: 1) Vehicle system id, this way ground station can request arm authorization on behalf of any vehicle;
	MAV_CMD_ARM_AUTHORIZATION_REQUEST MAV_CMD = 3001
	// MAV_CMD_SET_GUIDED_SUBMODE_STANDARD enum. 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
	MAV_CMD_SET_GUIDED_SUBMODE_STANDARD MAV_CMD = 4000
	// MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE enum. 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. Params: 1) Radius of desired circle in CIRCLE_MODE; 2) User defined; 3) User defined; 4) User defined; 5) Target latitude of center of circle in CIRCLE_MODE; 6) Target longitude of center of circle in CIRCLE_MODE;
	MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE MAV_CMD = 4001
	// MAV_CMD_CONDITION_GATE enum. Delay mission state machine until gate has been reached. Params: 1) Geometry: 0: orthogonal to path between previous and next waypoint.; 2) Altitude: 0: ignore altitude; 3) Empty; 4) Empty; 5) Latitude; 6) Longitude; 7) Altitude;
	MAV_CMD_CONDITION_GATE MAV_CMD = 4501
	// MAV_CMD_NAV_FENCE_RETURN_POINT enum. Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead. Params: 1) Reserved; 2) Reserved; 3) Reserved; 4) Reserved; 5) Latitude; 6) Longitude; 7) Altitude;
	MAV_CMD_NAV_FENCE_RETURN_POINT MAV_CMD = 5000
	// MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION enum. 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. Params: 1) Polygon vertex count; 2) Vehicle must be inside ALL inclusion zones in a single group, vehicle must be inside at least one group, must be the same for all points in each polygon; 3) Reserved; 4) Reserved; 5) Latitude; 6) Longitude; 7) Reserved;
	MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION MAV_CMD = 5001
	// MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION enum. 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. Params: 1) Polygon vertex count; 2) Reserved; 3) Reserved; 4) Reserved; 5) Latitude; 6) Longitude; 7) Reserved;
	MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION MAV_CMD = 5002
	// MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION enum. Circular fence area. The vehicle must stay inside this area. Params: 1) Radius.; 2) Vehicle must be inside ALL inclusion zones in a single group, vehicle must be inside at least one group; 3) Reserved; 4) Reserved; 5) Latitude; 6) Longitude; 7) Reserved;
	MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION MAV_CMD = 5003
	// MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION enum. Circular fence area. The vehicle must stay outside this area. Params: 1) Radius.; 2) Reserved; 3) Reserved; 4) Reserved; 5) Latitude; 6) Longitude; 7) Reserved;
	MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION MAV_CMD = 5004
	// MAV_CMD_NAV_RALLY_POINT enum. Rally point. You can have multiple rally points defined. Params: 1) Reserved; 2) Reserved; 3) Reserved; 4) Reserved; 5) Latitude; 6) Longitude; 7) Altitude;
	MAV_CMD_NAV_RALLY_POINT MAV_CMD = 5100
	// MAV_CMD_UAVCAN_GET_NODE_INFO enum. 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. Params: 1) Reserved (set to 0); 2) Reserved (set to 0); 3) Reserved (set to 0); 4) Reserved (set to 0); 5) Reserved (set to 0); 6) Reserved (set to 0); 7) Reserved (set to 0);
	MAV_CMD_UAVCAN_GET_NODE_INFO MAV_CMD = 5200
	// MAV_CMD_PAYLOAD_PREPARE_DEPLOY enum. Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. Params: 1) Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.; 2) Desired approach vector in compass heading. A negative value indicates the system can define the approach vector at will.; 3) Desired ground speed at release time. This can be overridden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.; 4) Minimum altitude clearance to the release position. A negative value indicates the system can define the clearance at will.; 5) Latitude. Note, if used in MISSION_ITEM (deprecated) the units are degrees (unscaled); 6) Longitude. Note, if used in MISSION_ITEM (deprecated) the units are degrees (unscaled); 7) Altitude (MSL);
	MAV_CMD_PAYLOAD_PREPARE_DEPLOY MAV_CMD = 30001
	// MAV_CMD_PAYLOAD_CONTROL_DEPLOY enum. Control the payload deployment. Params: 1) Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deployment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.; 2) Reserved; 3) Reserved; 4) Reserved; 5) Reserved; 6) Reserved; 7) Reserved;
	MAV_CMD_PAYLOAD_CONTROL_DEPLOY MAV_CMD = 30002
	// MAV_CMD_FIXED_MAG_CAL_YAW enum. Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. Params: 1) Yaw of vehicle in earth frame.; 2) CompassMask, 0 for all.; 3) Latitude.; 4) Longitude.; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_FIXED_MAG_CAL_YAW MAV_CMD = 42006
	// MAV_CMD_DO_WINCH enum. Command to operate winch. Params: 1) Winch instance number.; 2) Action to perform.; 3) Length of cable to release (negative to wind).; 4) Release rate (negative to wind).; 5) Empty.; 6) Empty.; 7) Empty.;
	MAV_CMD_DO_WINCH MAV_CMD = 42600
	// MAV_CMD_WAYPOINT_USER_1 enum. User defined waypoint item. Ground Station will show the Vehicle as flying through this item. Params: 1) User defined; 2) User defined; 3) User defined; 4) User defined; 5) Latitude unscaled; 6) Longitude unscaled; 7) Altitude (MSL);
	MAV_CMD_WAYPOINT_USER_1 MAV_CMD = 31000
	// MAV_CMD_WAYPOINT_USER_2 enum. User defined waypoint item. Ground Station will show the Vehicle as flying through this item. Params: 1) User defined; 2) User defined; 3) User defined; 4) User defined; 5) Latitude unscaled; 6) Longitude unscaled; 7) Altitude (MSL);
	MAV_CMD_WAYPOINT_USER_2 MAV_CMD = 31001
	// MAV_CMD_WAYPOINT_USER_3 enum. User defined waypoint item. Ground Station will show the Vehicle as flying through this item. Params: 1) User defined; 2) User defined; 3) User defined; 4) User defined; 5) Latitude unscaled; 6) Longitude unscaled; 7) Altitude (MSL);
	MAV_CMD_WAYPOINT_USER_3 MAV_CMD = 31002
	// MAV_CMD_WAYPOINT_USER_4 enum. User defined waypoint item. Ground Station will show the Vehicle as flying through this item. Params: 1) User defined; 2) User defined; 3) User defined; 4) User defined; 5) Latitude unscaled; 6) Longitude unscaled; 7) Altitude (MSL);
	MAV_CMD_WAYPOINT_USER_4 MAV_CMD = 31003
	// MAV_CMD_WAYPOINT_USER_5 enum. User defined waypoint item. Ground Station will show the Vehicle as flying through this item. Params: 1) User defined; 2) User defined; 3) User defined; 4) User defined; 5) Latitude unscaled; 6) Longitude unscaled; 7) Altitude (MSL);
	MAV_CMD_WAYPOINT_USER_5 MAV_CMD = 31004
	// MAV_CMD_SPATIAL_USER_1 enum. User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. Params: 1) User defined; 2) User defined; 3) User defined; 4) User defined; 5) Latitude unscaled; 6) Longitude unscaled; 7) Altitude (MSL);
	MAV_CMD_SPATIAL_USER_1 MAV_CMD = 31005
	// MAV_CMD_SPATIAL_USER_2 enum. User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. Params: 1) User defined; 2) User defined; 3) User defined; 4) User defined; 5) Latitude unscaled; 6) Longitude unscaled; 7) Altitude (MSL);
	MAV_CMD_SPATIAL_USER_2 MAV_CMD = 31006
	// MAV_CMD_SPATIAL_USER_3 enum. User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. Params: 1) User defined; 2) User defined; 3) User defined; 4) User defined; 5) Latitude unscaled; 6) Longitude unscaled; 7) Altitude (MSL);
	MAV_CMD_SPATIAL_USER_3 MAV_CMD = 31007
	// MAV_CMD_SPATIAL_USER_4 enum. User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. Params: 1) User defined; 2) User defined; 3) User defined; 4) User defined; 5) Latitude unscaled; 6) Longitude unscaled; 7) Altitude (MSL);
	MAV_CMD_SPATIAL_USER_4 MAV_CMD = 31008
	// MAV_CMD_SPATIAL_USER_5 enum. User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. Params: 1) User defined; 2) User defined; 3) User defined; 4) User defined; 5) Latitude unscaled; 6) Longitude unscaled; 7) Altitude (MSL);
	MAV_CMD_SPATIAL_USER_5 MAV_CMD = 31009
	// MAV_CMD_USER_1 enum. User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. Params: 1) User defined; 2) User defined; 3) User defined; 4) User defined; 5) User defined; 6) User defined; 7) User defined;
	MAV_CMD_USER_1 MAV_CMD = 31010
	// MAV_CMD_USER_2 enum. User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. Params: 1) User defined; 2) User defined; 3) User defined; 4) User defined; 5) User defined; 6) User defined; 7) User defined;
	MAV_CMD_USER_2 MAV_CMD = 31011
	// MAV_CMD_USER_3 enum. User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. Params: 1) User defined; 2) User defined; 3) User defined; 4) User defined; 5) User defined; 6) User defined; 7) User defined;
	MAV_CMD_USER_3 MAV_CMD = 31012
	// MAV_CMD_USER_4 enum. User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. Params: 1) User defined; 2) User defined; 3) User defined; 4) User defined; 5) User defined; 6) User defined; 7) User defined;
	MAV_CMD_USER_4 MAV_CMD = 31013
	// MAV_CMD_USER_5 enum. User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. Params: 1) User defined; 2) User defined; 3) User defined; 4) User defined; 5) User defined; 6) User defined; 7) User defined;
	MAV_CMD_USER_5 MAV_CMD = 31014
	// MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW enum. Command to a gimbal manager to control the gimbal tilt and pan angles. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. A gimbal device is never to react to this command. Params: 1) Pitch/tilt angle (positive: tilt up, NaN to be ignored).; 2) Yaw/pan angle (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored).; 3) Pitch/tilt rate (positive: tilt up, NaN to be ignored).; 4) Yaw/pan rate (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored).; 5) Gimbal device flags.; 6) Gimbal manager flags.; 7) Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). The client is copied into bits 8-15.;
	MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW MAV_CMD = 60002
	// MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP enum. Command to configure a gimbal manager. A gimbal device is never to react to this command. The selected profile is reported in the STORM32_GIMBAL_MANAGER_STATUS message. Params: 1) Gimbal manager profile (0 = default).; 2) Gimbal manager setup flags (0 = none).; 7) Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.;
	MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP MAV_CMD = 60010
	// MAV_CMD_STORM32_DO_GIMBAL_ACTION enum. Command to initiate gimbal actions. Usually performed by the gimbal device, but some can also be done by the gimbal manager. It is hence best to broadcast this command. Params: 1) Gimbal action to initiate (0 = none).; 7) Gimbal ID of the gimbal to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.;
	MAV_CMD_STORM32_DO_GIMBAL_ACTION MAV_CMD = 60011
	// MAV_CMD_QSHOT_DO_CONFIGURE enum. Command to set the shot manager mode. Params: 1) Set shot mode.; 2) Set shot state or command. The allowed values are specific to the selected shot mode.;
	MAV_CMD_QSHOT_DO_CONFIGURE MAV_CMD = 60020
)

func (MAV_CMD) Bitmask

func (e MAV_CMD) Bitmask() string

Bitmask return string representetion of intersects MAV_CMD enums

func (MAV_CMD) MarshalBinary

func (e MAV_CMD) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_CMD) String

func (e MAV_CMD) String() string

func (*MAV_CMD) UnmarshalBinary

func (e *MAV_CMD) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_CMD_ACK

type MAV_CMD_ACK int

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

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

func (MAV_CMD_ACK) Bitmask

func (e MAV_CMD_ACK) Bitmask() string

Bitmask return string representetion of intersects MAV_CMD_ACK enums

func (MAV_CMD_ACK) MarshalBinary

func (e MAV_CMD_ACK) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_CMD_ACK) String

func (e MAV_CMD_ACK) String() string

func (*MAV_CMD_ACK) UnmarshalBinary

func (e *MAV_CMD_ACK) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_COLLISION_ACTION

type MAV_COLLISION_ACTION int

MAV_COLLISION_ACTION type. Possible actions an aircraft can take to avoid a collision.

const (
	// MAV_COLLISION_ACTION_NONE enum. Ignore any potential collisions
	MAV_COLLISION_ACTION_NONE MAV_COLLISION_ACTION = 0
	// MAV_COLLISION_ACTION_REPORT enum. Report potential collision
	MAV_COLLISION_ACTION_REPORT MAV_COLLISION_ACTION = 1
	// MAV_COLLISION_ACTION_ASCEND_OR_DESCEND enum. Ascend or Descend to avoid threat
	MAV_COLLISION_ACTION_ASCEND_OR_DESCEND MAV_COLLISION_ACTION = 2
	// MAV_COLLISION_ACTION_MOVE_HORIZONTALLY enum. Move horizontally to avoid threat
	MAV_COLLISION_ACTION_MOVE_HORIZONTALLY MAV_COLLISION_ACTION = 3
	// MAV_COLLISION_ACTION_MOVE_PERPENDICULAR enum. Aircraft to move perpendicular to the collision's velocity vector
	MAV_COLLISION_ACTION_MOVE_PERPENDICULAR MAV_COLLISION_ACTION = 4
	// MAV_COLLISION_ACTION_RTL enum. Aircraft to fly directly back to its launch point
	MAV_COLLISION_ACTION_RTL MAV_COLLISION_ACTION = 5
	// MAV_COLLISION_ACTION_HOVER enum. Aircraft to stop in place
	MAV_COLLISION_ACTION_HOVER MAV_COLLISION_ACTION = 6
)

func (MAV_COLLISION_ACTION) Bitmask

func (e MAV_COLLISION_ACTION) Bitmask() string

Bitmask return string representetion of intersects MAV_COLLISION_ACTION enums

func (MAV_COLLISION_ACTION) MarshalBinary

func (e MAV_COLLISION_ACTION) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_COLLISION_ACTION) String

func (e MAV_COLLISION_ACTION) String() string

func (*MAV_COLLISION_ACTION) UnmarshalBinary

func (e *MAV_COLLISION_ACTION) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_COLLISION_SRC

type MAV_COLLISION_SRC int

MAV_COLLISION_SRC type. Source of information about this collision.

const (
	// MAV_COLLISION_SRC_ADSB enum. ID field references ADSB_VEHICLE packets
	MAV_COLLISION_SRC_ADSB MAV_COLLISION_SRC = 0
	// MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT enum. ID field references MAVLink SRC ID
	MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT MAV_COLLISION_SRC = 1
)

func (MAV_COLLISION_SRC) Bitmask

func (e MAV_COLLISION_SRC) Bitmask() string

Bitmask return string representetion of intersects MAV_COLLISION_SRC enums

func (MAV_COLLISION_SRC) MarshalBinary

func (e MAV_COLLISION_SRC) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_COLLISION_SRC) String

func (e MAV_COLLISION_SRC) String() string

func (*MAV_COLLISION_SRC) UnmarshalBinary

func (e *MAV_COLLISION_SRC) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_COLLISION_THREAT_LEVEL

type MAV_COLLISION_THREAT_LEVEL int

MAV_COLLISION_THREAT_LEVEL type. Aircraft-rated danger from this threat.

const (
	// MAV_COLLISION_THREAT_LEVEL_NONE enum. Not a threat
	MAV_COLLISION_THREAT_LEVEL_NONE MAV_COLLISION_THREAT_LEVEL = 0
	// MAV_COLLISION_THREAT_LEVEL_LOW enum. Craft is mildly concerned about this threat
	MAV_COLLISION_THREAT_LEVEL_LOW MAV_COLLISION_THREAT_LEVEL = 1
	// MAV_COLLISION_THREAT_LEVEL_HIGH enum. Craft is panicking, and may take actions to avoid threat
	MAV_COLLISION_THREAT_LEVEL_HIGH MAV_COLLISION_THREAT_LEVEL = 2
)

func (MAV_COLLISION_THREAT_LEVEL) Bitmask

func (e MAV_COLLISION_THREAT_LEVEL) Bitmask() string

Bitmask return string representetion of intersects MAV_COLLISION_THREAT_LEVEL enums

func (MAV_COLLISION_THREAT_LEVEL) MarshalBinary

func (e MAV_COLLISION_THREAT_LEVEL) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_COLLISION_THREAT_LEVEL) String

func (*MAV_COLLISION_THREAT_LEVEL) UnmarshalBinary

func (e *MAV_COLLISION_THREAT_LEVEL) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_COMPONENT

type MAV_COMPONENT int

MAV_COMPONENT type. Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded.

const (
	// MAV_COMP_ID_ALL enum. Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message
	MAV_COMP_ID_ALL MAV_COMPONENT = 0
	// MAV_COMP_ID_AUTOPILOT1 enum. System flight controller component ("autopilot"). Only one autopilot is expected in a particular system
	MAV_COMP_ID_AUTOPILOT1 MAV_COMPONENT = 1
	// MAV_COMP_ID_USER1 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER1 MAV_COMPONENT = 25
	// MAV_COMP_ID_USER2 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER2 MAV_COMPONENT = 26
	// MAV_COMP_ID_USER3 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER3 MAV_COMPONENT = 27
	// MAV_COMP_ID_USER4 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER4 MAV_COMPONENT = 28
	// MAV_COMP_ID_USER5 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER5 MAV_COMPONENT = 29
	// MAV_COMP_ID_USER6 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER6 MAV_COMPONENT = 30
	// MAV_COMP_ID_USER7 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER7 MAV_COMPONENT = 31
	// MAV_COMP_ID_USER8 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER8 MAV_COMPONENT = 32
	// MAV_COMP_ID_USER9 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER9 MAV_COMPONENT = 33
	// MAV_COMP_ID_USER10 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER10 MAV_COMPONENT = 34
	// MAV_COMP_ID_USER11 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER11 MAV_COMPONENT = 35
	// MAV_COMP_ID_USER12 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER12 MAV_COMPONENT = 36
	// MAV_COMP_ID_USER13 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER13 MAV_COMPONENT = 37
	// MAV_COMP_ID_USER14 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER14 MAV_COMPONENT = 38
	// MAV_COMP_ID_USER15 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER15 MAV_COMPONENT = 39
	// MAV_COMP_ID_USER16 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER16 MAV_COMPONENT = 40
	// MAV_COMP_ID_USER17 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER17 MAV_COMPONENT = 41
	// MAV_COMP_ID_USER18 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER18 MAV_COMPONENT = 42
	// MAV_COMP_ID_USER19 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER19 MAV_COMPONENT = 43
	// MAV_COMP_ID_USER20 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER20 MAV_COMPONENT = 44
	// MAV_COMP_ID_USER21 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER21 MAV_COMPONENT = 45
	// MAV_COMP_ID_USER22 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER22 MAV_COMPONENT = 46
	// MAV_COMP_ID_USER23 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER23 MAV_COMPONENT = 47
	// MAV_COMP_ID_USER24 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER24 MAV_COMPONENT = 48
	// MAV_COMP_ID_USER25 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER25 MAV_COMPONENT = 49
	// MAV_COMP_ID_USER26 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER26 MAV_COMPONENT = 50
	// MAV_COMP_ID_USER27 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER27 MAV_COMPONENT = 51
	// MAV_COMP_ID_USER28 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER28 MAV_COMPONENT = 52
	// MAV_COMP_ID_USER29 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER29 MAV_COMPONENT = 53
	// MAV_COMP_ID_USER30 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER30 MAV_COMPONENT = 54
	// MAV_COMP_ID_USER31 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER31 MAV_COMPONENT = 55
	// MAV_COMP_ID_USER32 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER32 MAV_COMPONENT = 56
	// MAV_COMP_ID_USER33 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER33 MAV_COMPONENT = 57
	// MAV_COMP_ID_USER34 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER34 MAV_COMPONENT = 58
	// MAV_COMP_ID_USER35 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER35 MAV_COMPONENT = 59
	// MAV_COMP_ID_USER36 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER36 MAV_COMPONENT = 60
	// MAV_COMP_ID_USER37 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER37 MAV_COMPONENT = 61
	// MAV_COMP_ID_USER38 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER38 MAV_COMPONENT = 62
	// MAV_COMP_ID_USER39 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER39 MAV_COMPONENT = 63
	// MAV_COMP_ID_USER40 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER40 MAV_COMPONENT = 64
	// MAV_COMP_ID_USER41 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER41 MAV_COMPONENT = 65
	// MAV_COMP_ID_USER42 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER42 MAV_COMPONENT = 66
	// MAV_COMP_ID_USER43 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER43 MAV_COMPONENT = 67
	// MAV_COMP_ID_TELEMETRY_RADIO enum. Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages)
	MAV_COMP_ID_TELEMETRY_RADIO MAV_COMPONENT = 68
	// MAV_COMP_ID_USER45 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER45 MAV_COMPONENT = 69
	// MAV_COMP_ID_USER46 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER46 MAV_COMPONENT = 70
	// MAV_COMP_ID_USER47 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER47 MAV_COMPONENT = 71
	// MAV_COMP_ID_USER48 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER48 MAV_COMPONENT = 72
	// MAV_COMP_ID_USER49 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER49 MAV_COMPONENT = 73
	// MAV_COMP_ID_USER50 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER50 MAV_COMPONENT = 74
	// MAV_COMP_ID_USER51 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER51 MAV_COMPONENT = 75
	// MAV_COMP_ID_USER52 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER52 MAV_COMPONENT = 76
	// MAV_COMP_ID_USER53 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER53 MAV_COMPONENT = 77
	// MAV_COMP_ID_USER54 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER54 MAV_COMPONENT = 78
	// MAV_COMP_ID_USER55 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER55 MAV_COMPONENT = 79
	// MAV_COMP_ID_USER56 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER56 MAV_COMPONENT = 80
	// MAV_COMP_ID_USER57 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER57 MAV_COMPONENT = 81
	// MAV_COMP_ID_USER58 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER58 MAV_COMPONENT = 82
	// MAV_COMP_ID_USER59 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER59 MAV_COMPONENT = 83
	// MAV_COMP_ID_USER60 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER60 MAV_COMPONENT = 84
	// MAV_COMP_ID_USER61 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER61 MAV_COMPONENT = 85
	// MAV_COMP_ID_USER62 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER62 MAV_COMPONENT = 86
	// MAV_COMP_ID_USER63 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER63 MAV_COMPONENT = 87
	// MAV_COMP_ID_USER64 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER64 MAV_COMPONENT = 88
	// MAV_COMP_ID_USER65 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER65 MAV_COMPONENT = 89
	// MAV_COMP_ID_USER66 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER66 MAV_COMPONENT = 90
	// MAV_COMP_ID_USER67 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER67 MAV_COMPONENT = 91
	// MAV_COMP_ID_USER68 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER68 MAV_COMPONENT = 92
	// MAV_COMP_ID_USER69 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER69 MAV_COMPONENT = 93
	// MAV_COMP_ID_USER70 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER70 MAV_COMPONENT = 94
	// MAV_COMP_ID_USER71 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER71 MAV_COMPONENT = 95
	// MAV_COMP_ID_USER72 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER72 MAV_COMPONENT = 96
	// MAV_COMP_ID_USER73 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER73 MAV_COMPONENT = 97
	// MAV_COMP_ID_USER74 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER74 MAV_COMPONENT = 98
	// MAV_COMP_ID_USER75 enum. Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network
	MAV_COMP_ID_USER75 MAV_COMPONENT = 99
	// MAV_COMP_ID_CAMERA enum. Camera #1
	MAV_COMP_ID_CAMERA MAV_COMPONENT = 100
	// MAV_COMP_ID_CAMERA2 enum. Camera #2
	MAV_COMP_ID_CAMERA2 MAV_COMPONENT = 101
	// MAV_COMP_ID_CAMERA3 enum. Camera #3
	MAV_COMP_ID_CAMERA3 MAV_COMPONENT = 102
	// MAV_COMP_ID_CAMERA4 enum. Camera #4
	MAV_COMP_ID_CAMERA4 MAV_COMPONENT = 103
	// MAV_COMP_ID_CAMERA5 enum. Camera #5
	MAV_COMP_ID_CAMERA5 MAV_COMPONENT = 104
	// MAV_COMP_ID_CAMERA6 enum. Camera #6
	MAV_COMP_ID_CAMERA6 MAV_COMPONENT = 105
	// MAV_COMP_ID_SERVO1 enum. Servo #1
	MAV_COMP_ID_SERVO1 MAV_COMPONENT = 140
	// MAV_COMP_ID_SERVO2 enum. Servo #2
	MAV_COMP_ID_SERVO2 MAV_COMPONENT = 141
	// MAV_COMP_ID_SERVO3 enum. Servo #3
	MAV_COMP_ID_SERVO3 MAV_COMPONENT = 142
	// MAV_COMP_ID_SERVO4 enum. Servo #4
	MAV_COMP_ID_SERVO4 MAV_COMPONENT = 143
	// MAV_COMP_ID_SERVO5 enum. Servo #5
	MAV_COMP_ID_SERVO5 MAV_COMPONENT = 144
	// MAV_COMP_ID_SERVO6 enum. Servo #6
	MAV_COMP_ID_SERVO6 MAV_COMPONENT = 145
	// MAV_COMP_ID_SERVO7 enum. Servo #7
	MAV_COMP_ID_SERVO7 MAV_COMPONENT = 146
	// MAV_COMP_ID_SERVO8 enum. Servo #8
	MAV_COMP_ID_SERVO8 MAV_COMPONENT = 147
	// MAV_COMP_ID_SERVO9 enum. Servo #9
	MAV_COMP_ID_SERVO9 MAV_COMPONENT = 148
	// MAV_COMP_ID_SERVO10 enum. Servo #10
	MAV_COMP_ID_SERVO10 MAV_COMPONENT = 149
	// MAV_COMP_ID_SERVO11 enum. Servo #11
	MAV_COMP_ID_SERVO11 MAV_COMPONENT = 150
	// MAV_COMP_ID_SERVO12 enum. Servo #12
	MAV_COMP_ID_SERVO12 MAV_COMPONENT = 151
	// MAV_COMP_ID_SERVO13 enum. Servo #13
	MAV_COMP_ID_SERVO13 MAV_COMPONENT = 152
	// MAV_COMP_ID_SERVO14 enum. Servo #14
	MAV_COMP_ID_SERVO14 MAV_COMPONENT = 153
	// MAV_COMP_ID_GIMBAL enum. Gimbal #1
	MAV_COMP_ID_GIMBAL MAV_COMPONENT = 154
	// MAV_COMP_ID_LOG enum. Logging component
	MAV_COMP_ID_LOG MAV_COMPONENT = 155
	// MAV_COMP_ID_ADSB enum. Automatic Dependent Surveillance-Broadcast (ADS-B) component
	MAV_COMP_ID_ADSB MAV_COMPONENT = 156
	// MAV_COMP_ID_OSD enum. On Screen Display (OSD) devices for video links
	MAV_COMP_ID_OSD MAV_COMPONENT = 157
	// MAV_COMP_ID_PERIPHERAL enum. Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice
	MAV_COMP_ID_PERIPHERAL MAV_COMPONENT = 158
	// MAV_COMP_ID_QX1_GIMBAL enum. Gimbal ID for QX1
	MAV_COMP_ID_QX1_GIMBAL MAV_COMPONENT = 159
	// MAV_COMP_ID_FLARM enum. FLARM collision alert component
	MAV_COMP_ID_FLARM MAV_COMPONENT = 160
	// MAV_COMP_ID_GIMBAL2 enum. Gimbal #2
	MAV_COMP_ID_GIMBAL2 MAV_COMPONENT = 171
	// MAV_COMP_ID_GIMBAL3 enum. Gimbal #3
	MAV_COMP_ID_GIMBAL3 MAV_COMPONENT = 172
	// MAV_COMP_ID_GIMBAL4 enum. Gimbal #4
	MAV_COMP_ID_GIMBAL4 MAV_COMPONENT = 173
	// MAV_COMP_ID_GIMBAL5 enum. Gimbal #5
	MAV_COMP_ID_GIMBAL5 MAV_COMPONENT = 174
	// MAV_COMP_ID_GIMBAL6 enum. Gimbal #6
	MAV_COMP_ID_GIMBAL6 MAV_COMPONENT = 175
	// MAV_COMP_ID_MISSIONPLANNER enum. Component that can generate/supply a mission flight plan (e.g. GCS or developer API)
	MAV_COMP_ID_MISSIONPLANNER MAV_COMPONENT = 190
	// MAV_COMP_ID_ONBOARD_COMPUTER enum. Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on
	MAV_COMP_ID_ONBOARD_COMPUTER MAV_COMPONENT = 191
	// MAV_COMP_ID_PATHPLANNER enum. Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.)
	MAV_COMP_ID_PATHPLANNER MAV_COMPONENT = 195
	// MAV_COMP_ID_OBSTACLE_AVOIDANCE enum. Component that plans a collision free path between two points
	MAV_COMP_ID_OBSTACLE_AVOIDANCE MAV_COMPONENT = 196
	// MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY enum. Component that provides position estimates using VIO techniques
	MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY MAV_COMPONENT = 197
	// MAV_COMP_ID_PAIRING_MANAGER enum. Component that manages pairing of vehicle and GCS
	MAV_COMP_ID_PAIRING_MANAGER MAV_COMPONENT = 198
	// MAV_COMP_ID_IMU enum. Inertial Measurement Unit (IMU) #1
	MAV_COMP_ID_IMU MAV_COMPONENT = 200
	// MAV_COMP_ID_IMU_2 enum. Inertial Measurement Unit (IMU) #2
	MAV_COMP_ID_IMU_2 MAV_COMPONENT = 201
	// MAV_COMP_ID_IMU_3 enum. Inertial Measurement Unit (IMU) #3
	MAV_COMP_ID_IMU_3 MAV_COMPONENT = 202
	// MAV_COMP_ID_GPS enum. GPS #1
	MAV_COMP_ID_GPS MAV_COMPONENT = 220
	// MAV_COMP_ID_GPS2 enum. GPS #2
	MAV_COMP_ID_GPS2 MAV_COMPONENT = 221
	// MAV_COMP_ID_ODID_TXRX_1 enum. Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)
	MAV_COMP_ID_ODID_TXRX_1 MAV_COMPONENT = 236
	// MAV_COMP_ID_ODID_TXRX_2 enum. Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)
	MAV_COMP_ID_ODID_TXRX_2 MAV_COMPONENT = 237
	// MAV_COMP_ID_ODID_TXRX_3 enum. Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)
	MAV_COMP_ID_ODID_TXRX_3 MAV_COMPONENT = 238
	// MAV_COMP_ID_UDP_BRIDGE enum. Component to bridge MAVLink to UDP (i.e. from a UART)
	MAV_COMP_ID_UDP_BRIDGE MAV_COMPONENT = 240
	// MAV_COMP_ID_UART_BRIDGE enum. Component to bridge to UART (i.e. from UDP)
	MAV_COMP_ID_UART_BRIDGE MAV_COMPONENT = 241
	// MAV_COMP_ID_TUNNEL_NODE enum. Component handling TUNNEL messages (e.g. vendor specific GUI of a component)
	MAV_COMP_ID_TUNNEL_NODE MAV_COMPONENT = 242
	// MAV_COMP_ID_SYSTEM_CONTROL enum. Component for handling system messages (e.g. to ARM, takeoff, etc.)
	MAV_COMP_ID_SYSTEM_CONTROL MAV_COMPONENT = 250
)

func (MAV_COMPONENT) Bitmask

func (e MAV_COMPONENT) Bitmask() string

Bitmask return string representetion of intersects MAV_COMPONENT enums

func (MAV_COMPONENT) MarshalBinary

func (e MAV_COMPONENT) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_COMPONENT) String

func (e MAV_COMPONENT) String() string

func (*MAV_COMPONENT) UnmarshalBinary

func (e *MAV_COMPONENT) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_DATA_STREAM

type MAV_DATA_STREAM int

MAV_DATA_STREAM type. A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages.

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

func (MAV_DATA_STREAM) Bitmask

func (e MAV_DATA_STREAM) Bitmask() string

Bitmask return string representetion of intersects MAV_DATA_STREAM enums

func (MAV_DATA_STREAM) MarshalBinary

func (e MAV_DATA_STREAM) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_DATA_STREAM) String

func (e MAV_DATA_STREAM) String() string

func (*MAV_DATA_STREAM) UnmarshalBinary

func (e *MAV_DATA_STREAM) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_DISTANCE_SENSOR

type MAV_DISTANCE_SENSOR int

MAV_DISTANCE_SENSOR type. Enumeration of distance sensor types

const (
	// MAV_DISTANCE_SENSOR_LASER enum. Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units
	MAV_DISTANCE_SENSOR_LASER MAV_DISTANCE_SENSOR = 0
	// MAV_DISTANCE_SENSOR_ULTRASOUND enum. Ultrasound rangefinder, e.g. MaxBotix units
	MAV_DISTANCE_SENSOR_ULTRASOUND MAV_DISTANCE_SENSOR = 1
	// MAV_DISTANCE_SENSOR_INFRARED enum. Infrared rangefinder, e.g. Sharp units
	MAV_DISTANCE_SENSOR_INFRARED MAV_DISTANCE_SENSOR = 2
	// MAV_DISTANCE_SENSOR_RADAR enum. Radar type, e.g. uLanding units
	MAV_DISTANCE_SENSOR_RADAR MAV_DISTANCE_SENSOR = 3
	// MAV_DISTANCE_SENSOR_UNKNOWN enum. Broken or unknown type, e.g. analog units
	MAV_DISTANCE_SENSOR_UNKNOWN MAV_DISTANCE_SENSOR = 4
)

func (MAV_DISTANCE_SENSOR) Bitmask

func (e MAV_DISTANCE_SENSOR) Bitmask() string

Bitmask return string representetion of intersects MAV_DISTANCE_SENSOR enums

func (MAV_DISTANCE_SENSOR) MarshalBinary

func (e MAV_DISTANCE_SENSOR) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_DISTANCE_SENSOR) String

func (e MAV_DISTANCE_SENSOR) String() string

func (*MAV_DISTANCE_SENSOR) UnmarshalBinary

func (e *MAV_DISTANCE_SENSOR) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_DO_REPOSITION_FLAGS

type MAV_DO_REPOSITION_FLAGS int

MAV_DO_REPOSITION_FLAGS type. Bitmap of options for the MAV_CMD_DO_REPOSITION

const (
	// MAV_DO_REPOSITION_FLAGS_CHANGE_MODE enum. The aircraft should immediately transition into guided. This should not be set for follow me applications
	MAV_DO_REPOSITION_FLAGS_CHANGE_MODE MAV_DO_REPOSITION_FLAGS = 1
)

func (MAV_DO_REPOSITION_FLAGS) Bitmask

func (e MAV_DO_REPOSITION_FLAGS) Bitmask() string

Bitmask return string representetion of intersects MAV_DO_REPOSITION_FLAGS enums

func (MAV_DO_REPOSITION_FLAGS) MarshalBinary

func (e MAV_DO_REPOSITION_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_DO_REPOSITION_FLAGS) String

func (e MAV_DO_REPOSITION_FLAGS) String() string

func (*MAV_DO_REPOSITION_FLAGS) UnmarshalBinary

func (e *MAV_DO_REPOSITION_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ESTIMATOR_TYPE

type MAV_ESTIMATOR_TYPE int

MAV_ESTIMATOR_TYPE type. Enumeration of estimator types

const (
	// MAV_ESTIMATOR_TYPE_UNKNOWN enum. Unknown type of the estimator
	MAV_ESTIMATOR_TYPE_UNKNOWN MAV_ESTIMATOR_TYPE = 0
	// MAV_ESTIMATOR_TYPE_NAIVE enum. This is a naive estimator without any real covariance feedback
	MAV_ESTIMATOR_TYPE_NAIVE MAV_ESTIMATOR_TYPE = 1
	// MAV_ESTIMATOR_TYPE_VISION enum. Computer vision based estimate. Might be up to scale
	MAV_ESTIMATOR_TYPE_VISION MAV_ESTIMATOR_TYPE = 2
	// MAV_ESTIMATOR_TYPE_VIO enum. Visual-inertial estimate
	MAV_ESTIMATOR_TYPE_VIO MAV_ESTIMATOR_TYPE = 3
	// MAV_ESTIMATOR_TYPE_GPS enum. Plain GPS estimate
	MAV_ESTIMATOR_TYPE_GPS MAV_ESTIMATOR_TYPE = 4
	// MAV_ESTIMATOR_TYPE_GPS_INS enum. Estimator integrating GPS and inertial sensing
	MAV_ESTIMATOR_TYPE_GPS_INS MAV_ESTIMATOR_TYPE = 5
	// MAV_ESTIMATOR_TYPE_MOCAP enum. Estimate from external motion capturing system
	MAV_ESTIMATOR_TYPE_MOCAP MAV_ESTIMATOR_TYPE = 6
	// MAV_ESTIMATOR_TYPE_LIDAR enum. Estimator based on lidar sensor input
	MAV_ESTIMATOR_TYPE_LIDAR MAV_ESTIMATOR_TYPE = 7
	// MAV_ESTIMATOR_TYPE_AUTOPILOT enum. Estimator on autopilot
	MAV_ESTIMATOR_TYPE_AUTOPILOT MAV_ESTIMATOR_TYPE = 8
)

func (MAV_ESTIMATOR_TYPE) Bitmask

func (e MAV_ESTIMATOR_TYPE) Bitmask() string

Bitmask return string representetion of intersects MAV_ESTIMATOR_TYPE enums

func (MAV_ESTIMATOR_TYPE) MarshalBinary

func (e MAV_ESTIMATOR_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ESTIMATOR_TYPE) String

func (e MAV_ESTIMATOR_TYPE) String() string

func (*MAV_ESTIMATOR_TYPE) UnmarshalBinary

func (e *MAV_ESTIMATOR_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_FRAME

type MAV_FRAME int

MAV_FRAME type

const (
	// MAV_FRAME_GLOBAL enum. Global (WGS84) coordinate frame + MSL altitude. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL)
	MAV_FRAME_GLOBAL MAV_FRAME = 0
	// MAV_FRAME_LOCAL_NED enum. Local coordinate frame, Z-down (x: North, y: East, z: Down)
	MAV_FRAME_LOCAL_NED MAV_FRAME = 1
	// MAV_FRAME_MISSION enum. NOT a coordinate frame, indicates a mission command
	MAV_FRAME_MISSION MAV_FRAME = 2
	// MAV_FRAME_GLOBAL_RELATIVE_ALT enum. Global (WGS84) coordinate frame + altitude relative to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location
	MAV_FRAME_GLOBAL_RELATIVE_ALT MAV_FRAME = 3
	// MAV_FRAME_LOCAL_ENU enum. Local coordinate frame, Z-up (x: East, y: North, z: Up)
	MAV_FRAME_LOCAL_ENU MAV_FRAME = 4
	// MAV_FRAME_GLOBAL_INT enum. Global (WGS84) coordinate frame (scaled) + MSL altitude. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL)
	MAV_FRAME_GLOBAL_INT MAV_FRAME = 5
	// MAV_FRAME_GLOBAL_RELATIVE_ALT_INT enum. Global (WGS84) coordinate frame (scaled) + altitude relative to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location
	MAV_FRAME_GLOBAL_RELATIVE_ALT_INT MAV_FRAME = 6
	// MAV_FRAME_LOCAL_OFFSET_NED enum. Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position
	MAV_FRAME_LOCAL_OFFSET_NED MAV_FRAME = 7
	// MAV_FRAME_BODY_NED enum. Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right
	MAV_FRAME_BODY_NED MAV_FRAME = 8
	// MAV_FRAME_BODY_OFFSET_NED enum. Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east
	MAV_FRAME_BODY_OFFSET_NED MAV_FRAME = 9
	// MAV_FRAME_GLOBAL_TERRAIN_ALT enum. Global (WGS84) coordinate frame with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model
	MAV_FRAME_GLOBAL_TERRAIN_ALT MAV_FRAME = 10
	// MAV_FRAME_GLOBAL_TERRAIN_ALT_INT enum. Global (WGS84) coordinate frame (scaled) with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model
	MAV_FRAME_GLOBAL_TERRAIN_ALT_INT MAV_FRAME = 11
	// MAV_FRAME_BODY_FRD enum. Body fixed frame of reference, Z-down (x: Forward, y: Right, z: Down)
	MAV_FRAME_BODY_FRD MAV_FRAME = 12
	// MAV_FRAME_RESERVED_13 enum. MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up)
	MAV_FRAME_RESERVED_13 MAV_FRAME = 13
	// MAV_FRAME_RESERVED_14 enum. MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down)
	MAV_FRAME_RESERVED_14 MAV_FRAME = 14
	// MAV_FRAME_RESERVED_15 enum. MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up)
	MAV_FRAME_RESERVED_15 MAV_FRAME = 15
	// MAV_FRAME_RESERVED_16 enum. MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down)
	MAV_FRAME_RESERVED_16 MAV_FRAME = 16
	// MAV_FRAME_RESERVED_17 enum. MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up)
	MAV_FRAME_RESERVED_17 MAV_FRAME = 17
	// MAV_FRAME_RESERVED_18 enum. MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down)
	MAV_FRAME_RESERVED_18 MAV_FRAME = 18
	// MAV_FRAME_RESERVED_19 enum. MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up)
	MAV_FRAME_RESERVED_19 MAV_FRAME = 19
	// MAV_FRAME_LOCAL_FRD enum. Forward, Right, Down coordinate frame. This is a local frame with Z-down and arbitrary F/R alignment (i.e. not aligned with NED/earth frame)
	MAV_FRAME_LOCAL_FRD MAV_FRAME = 20
	// MAV_FRAME_LOCAL_FLU enum. Forward, Left, Up coordinate frame. This is a local frame with Z-up and arbitrary F/L alignment (i.e. not aligned with ENU/earth frame)
	MAV_FRAME_LOCAL_FLU MAV_FRAME = 21
)

func (MAV_FRAME) Bitmask

func (e MAV_FRAME) Bitmask() string

Bitmask return string representetion of intersects MAV_FRAME enums

func (MAV_FRAME) MarshalBinary

func (e MAV_FRAME) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_FRAME) String

func (e MAV_FRAME) String() string

func (*MAV_FRAME) UnmarshalBinary

func (e *MAV_FRAME) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_GENERATOR_STATUS_FLAG

type MAV_GENERATOR_STATUS_FLAG int

MAV_GENERATOR_STATUS_FLAG type. Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly).

const (
	// MAV_GENERATOR_STATUS_FLAG_OFF enum. Generator is off
	MAV_GENERATOR_STATUS_FLAG_OFF MAV_GENERATOR_STATUS_FLAG = 1
	// MAV_GENERATOR_STATUS_FLAG_READY enum. Generator is ready to start generating power
	MAV_GENERATOR_STATUS_FLAG_READY MAV_GENERATOR_STATUS_FLAG = 2
	// MAV_GENERATOR_STATUS_FLAG_GENERATING enum. Generator is generating power
	MAV_GENERATOR_STATUS_FLAG_GENERATING MAV_GENERATOR_STATUS_FLAG = 4
	// MAV_GENERATOR_STATUS_FLAG_CHARGING enum. Generator is charging the batteries (generating enough power to charge and provide the load)
	MAV_GENERATOR_STATUS_FLAG_CHARGING MAV_GENERATOR_STATUS_FLAG = 8
	// MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER enum. Generator is operating at a reduced maximum power
	MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER MAV_GENERATOR_STATUS_FLAG = 16
	// MAV_GENERATOR_STATUS_FLAG_MAXPOWER enum. Generator is providing the maximum output
	MAV_GENERATOR_STATUS_FLAG_MAXPOWER MAV_GENERATOR_STATUS_FLAG = 32
	// MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING enum. Generator is near the maximum operating temperature, cooling is insufficient
	MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING MAV_GENERATOR_STATUS_FLAG = 64
	// MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT enum. Generator hit the maximum operating temperature and shutdown
	MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT MAV_GENERATOR_STATUS_FLAG = 128
	// MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING enum. Power electronics are near the maximum operating temperature, cooling is insufficient
	MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING MAV_GENERATOR_STATUS_FLAG = 256
	// MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT enum. Power electronics hit the maximum operating temperature and shutdown
	MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT MAV_GENERATOR_STATUS_FLAG = 512
	// MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT enum. Power electronics experienced a fault and shutdown
	MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT MAV_GENERATOR_STATUS_FLAG = 1024
	// MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT enum. The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening
	MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT MAV_GENERATOR_STATUS_FLAG = 2048
	// MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING enum. Generator controller having communication problems
	MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING MAV_GENERATOR_STATUS_FLAG = 4096
	// MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING enum. Power electronic or generator cooling system error
	MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING MAV_GENERATOR_STATUS_FLAG = 8192
	// MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT enum. Generator controller power rail experienced a fault
	MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT MAV_GENERATOR_STATUS_FLAG = 16384
	// MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT enum. Generator controller exceeded the overcurrent threshold and shutdown to prevent damage
	MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT MAV_GENERATOR_STATUS_FLAG = 32768
	// MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT enum. Generator controller detected a high current going into the batteries and shutdown to prevent battery damage
	MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT MAV_GENERATOR_STATUS_FLAG = 65536
	// MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT enum. Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating
	MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT MAV_GENERATOR_STATUS_FLAG = 131072
	// MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT enum. Batteries are under voltage (generator will not start)
	MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT MAV_GENERATOR_STATUS_FLAG = 262144
	// MAV_GENERATOR_STATUS_FLAG_START_INHIBITED enum. Generator start is inhibited by e.g. a safety switch
	MAV_GENERATOR_STATUS_FLAG_START_INHIBITED MAV_GENERATOR_STATUS_FLAG = 524288
	// MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED enum. Generator requires maintenance
	MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED MAV_GENERATOR_STATUS_FLAG = 1048576
	// MAV_GENERATOR_STATUS_FLAG_WARMING_UP enum. Generator is not ready to generate yet
	MAV_GENERATOR_STATUS_FLAG_WARMING_UP MAV_GENERATOR_STATUS_FLAG = 2097152
	// MAV_GENERATOR_STATUS_FLAG_IDLE enum. Generator is idle
	MAV_GENERATOR_STATUS_FLAG_IDLE MAV_GENERATOR_STATUS_FLAG = 4194304
)

func (MAV_GENERATOR_STATUS_FLAG) Bitmask

func (e MAV_GENERATOR_STATUS_FLAG) Bitmask() string

Bitmask return string representetion of intersects MAV_GENERATOR_STATUS_FLAG enums

func (MAV_GENERATOR_STATUS_FLAG) MarshalBinary

func (e MAV_GENERATOR_STATUS_FLAG) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_GENERATOR_STATUS_FLAG) String

func (e MAV_GENERATOR_STATUS_FLAG) String() string

func (*MAV_GENERATOR_STATUS_FLAG) UnmarshalBinary

func (e *MAV_GENERATOR_STATUS_FLAG) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_GOTO

type MAV_GOTO int

MAV_GOTO type. Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution.

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

func (MAV_GOTO) Bitmask

func (e MAV_GOTO) Bitmask() string

Bitmask return string representetion of intersects MAV_GOTO enums

func (MAV_GOTO) MarshalBinary

func (e MAV_GOTO) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_GOTO) String

func (e MAV_GOTO) String() string

func (*MAV_GOTO) UnmarshalBinary

func (e *MAV_GOTO) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_LANDED_STATE

type MAV_LANDED_STATE int

MAV_LANDED_STATE type. Enumeration of landed detector states

const (
	// MAV_LANDED_STATE_UNDEFINED enum. MAV landed state is unknown
	MAV_LANDED_STATE_UNDEFINED MAV_LANDED_STATE = 0
	// MAV_LANDED_STATE_ON_GROUND enum. MAV is landed (on ground)
	MAV_LANDED_STATE_ON_GROUND MAV_LANDED_STATE = 1
	// MAV_LANDED_STATE_IN_AIR enum. MAV is in air
	MAV_LANDED_STATE_IN_AIR MAV_LANDED_STATE = 2
	// MAV_LANDED_STATE_TAKEOFF enum. MAV currently taking off
	MAV_LANDED_STATE_TAKEOFF MAV_LANDED_STATE = 3
	// MAV_LANDED_STATE_LANDING enum. MAV currently landing
	MAV_LANDED_STATE_LANDING MAV_LANDED_STATE = 4
)

func (MAV_LANDED_STATE) Bitmask

func (e MAV_LANDED_STATE) Bitmask() string

Bitmask return string representetion of intersects MAV_LANDED_STATE enums

func (MAV_LANDED_STATE) MarshalBinary

func (e MAV_LANDED_STATE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_LANDED_STATE) String

func (e MAV_LANDED_STATE) String() string

func (*MAV_LANDED_STATE) UnmarshalBinary

func (e *MAV_LANDED_STATE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_MISSION_RESULT

type MAV_MISSION_RESULT int

MAV_MISSION_RESULT type. Result of mission operation (in a MISSION_ACK message).

const (
	// MAV_MISSION_ACCEPTED enum. mission accepted OK
	MAV_MISSION_ACCEPTED MAV_MISSION_RESULT = 0
	// MAV_MISSION_ERROR enum. Generic error / not accepting mission commands at all right now
	MAV_MISSION_ERROR MAV_MISSION_RESULT = 1
	// MAV_MISSION_UNSUPPORTED_FRAME enum. Coordinate frame is not supported
	MAV_MISSION_UNSUPPORTED_FRAME MAV_MISSION_RESULT = 2
	// MAV_MISSION_UNSUPPORTED enum. Command is not supported
	MAV_MISSION_UNSUPPORTED MAV_MISSION_RESULT = 3
	// MAV_MISSION_NO_SPACE enum. Mission items exceed storage space
	MAV_MISSION_NO_SPACE MAV_MISSION_RESULT = 4
	// MAV_MISSION_INVALID enum. One of the parameters has an invalid value
	MAV_MISSION_INVALID MAV_MISSION_RESULT = 5
	// MAV_MISSION_INVALID_PARAM1 enum. param1 has an invalid value
	MAV_MISSION_INVALID_PARAM1 MAV_MISSION_RESULT = 6
	// MAV_MISSION_INVALID_PARAM2 enum. param2 has an invalid value
	MAV_MISSION_INVALID_PARAM2 MAV_MISSION_RESULT = 7
	// MAV_MISSION_INVALID_PARAM3 enum. param3 has an invalid value
	MAV_MISSION_INVALID_PARAM3 MAV_MISSION_RESULT = 8
	// MAV_MISSION_INVALID_PARAM4 enum. param4 has an invalid value
	MAV_MISSION_INVALID_PARAM4 MAV_MISSION_RESULT = 9
	// MAV_MISSION_INVALID_PARAM5_X enum. x / param5 has an invalid value
	MAV_MISSION_INVALID_PARAM5_X MAV_MISSION_RESULT = 10
	// MAV_MISSION_INVALID_PARAM6_Y enum. y / param6 has an invalid value
	MAV_MISSION_INVALID_PARAM6_Y MAV_MISSION_RESULT = 11
	// MAV_MISSION_INVALID_PARAM7 enum. z / param7 has an invalid value
	MAV_MISSION_INVALID_PARAM7 MAV_MISSION_RESULT = 12
	// MAV_MISSION_INVALID_SEQUENCE enum. Mission item received out of sequence
	MAV_MISSION_INVALID_SEQUENCE MAV_MISSION_RESULT = 13
	// MAV_MISSION_DENIED enum. Not accepting any mission commands from this communication partner
	MAV_MISSION_DENIED MAV_MISSION_RESULT = 14
	// MAV_MISSION_OPERATION_CANCELLED enum. Current mission operation cancelled (e.g. mission upload, mission download)
	MAV_MISSION_OPERATION_CANCELLED MAV_MISSION_RESULT = 15
)

func (MAV_MISSION_RESULT) Bitmask

func (e MAV_MISSION_RESULT) Bitmask() string

Bitmask return string representetion of intersects MAV_MISSION_RESULT enums

func (MAV_MISSION_RESULT) MarshalBinary

func (e MAV_MISSION_RESULT) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_MISSION_RESULT) String

func (e MAV_MISSION_RESULT) String() string

func (*MAV_MISSION_RESULT) UnmarshalBinary

func (e *MAV_MISSION_RESULT) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_MISSION_TYPE

type MAV_MISSION_TYPE int

MAV_MISSION_TYPE type. Type of mission items being requested/sent in mission protocol.

const (
	// MAV_MISSION_TYPE_MISSION enum. Items are mission commands for main mission
	MAV_MISSION_TYPE_MISSION MAV_MISSION_TYPE = 0
	// MAV_MISSION_TYPE_FENCE enum. Specifies GeoFence area(s). Items are MAV_CMD_NAV_FENCE_ GeoFence items
	MAV_MISSION_TYPE_FENCE MAV_MISSION_TYPE = 1
	// MAV_MISSION_TYPE_RALLY enum. Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_NAV_RALLY_POINT rally point items
	MAV_MISSION_TYPE_RALLY MAV_MISSION_TYPE = 2
	// MAV_MISSION_TYPE_ALL enum. Only used in MISSION_CLEAR_ALL to clear all mission types
	MAV_MISSION_TYPE_ALL MAV_MISSION_TYPE = 255
)

func (MAV_MISSION_TYPE) Bitmask

func (e MAV_MISSION_TYPE) Bitmask() string

Bitmask return string representetion of intersects MAV_MISSION_TYPE enums

func (MAV_MISSION_TYPE) MarshalBinary

func (e MAV_MISSION_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_MISSION_TYPE) String

func (e MAV_MISSION_TYPE) String() string

func (*MAV_MISSION_TYPE) UnmarshalBinary

func (e *MAV_MISSION_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_MODE

type MAV_MODE int

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

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

func (MAV_MODE) Bitmask

func (e MAV_MODE) Bitmask() string

Bitmask return string representetion of intersects MAV_MODE enums

func (MAV_MODE) MarshalBinary

func (e MAV_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_MODE) String

func (e MAV_MODE) String() string

func (*MAV_MODE) UnmarshalBinary

func (e *MAV_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_MODE_FLAG

type MAV_MODE_FLAG int

MAV_MODE_FLAG type. These flags encode the MAV mode.

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

func (MAV_MODE_FLAG) Bitmask

func (e MAV_MODE_FLAG) Bitmask() string

Bitmask return string representetion of intersects MAV_MODE_FLAG enums

func (MAV_MODE_FLAG) MarshalBinary

func (e MAV_MODE_FLAG) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_MODE_FLAG) String

func (e MAV_MODE_FLAG) String() string

func (*MAV_MODE_FLAG) UnmarshalBinary

func (e *MAV_MODE_FLAG) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_MODE_FLAG_DECODE_POSITION

type MAV_MODE_FLAG_DECODE_POSITION int

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

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

func (MAV_MODE_FLAG_DECODE_POSITION) Bitmask

Bitmask return string representetion of intersects MAV_MODE_FLAG_DECODE_POSITION enums

func (MAV_MODE_FLAG_DECODE_POSITION) MarshalBinary

func (e MAV_MODE_FLAG_DECODE_POSITION) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_MODE_FLAG_DECODE_POSITION) String

func (*MAV_MODE_FLAG_DECODE_POSITION) UnmarshalBinary

func (e *MAV_MODE_FLAG_DECODE_POSITION) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_MODE_GIMBAL

type MAV_MODE_GIMBAL int

MAV_MODE_GIMBAL type

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

func (MAV_MODE_GIMBAL) Bitmask

func (e MAV_MODE_GIMBAL) Bitmask() string

Bitmask return string representetion of intersects MAV_MODE_GIMBAL enums

func (MAV_MODE_GIMBAL) MarshalBinary

func (e MAV_MODE_GIMBAL) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_MODE_GIMBAL) String

func (e MAV_MODE_GIMBAL) String() string

func (*MAV_MODE_GIMBAL) UnmarshalBinary

func (e *MAV_MODE_GIMBAL) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_MOUNT_MODE

type MAV_MOUNT_MODE int

MAV_MOUNT_MODE type. Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages.

const (
	// MAV_MOUNT_MODE_RETRACT enum. Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization
	MAV_MOUNT_MODE_RETRACT MAV_MOUNT_MODE = 0
	// MAV_MOUNT_MODE_NEUTRAL enum. Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory
	MAV_MOUNT_MODE_NEUTRAL MAV_MOUNT_MODE = 1
	// MAV_MOUNT_MODE_MAVLINK_TARGETING enum. Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization
	MAV_MOUNT_MODE_MAVLINK_TARGETING MAV_MOUNT_MODE = 2
	// MAV_MOUNT_MODE_RC_TARGETING enum. Load neutral position and start RC Roll,Pitch,Yaw control with stabilization
	MAV_MOUNT_MODE_RC_TARGETING MAV_MOUNT_MODE = 3
	// MAV_MOUNT_MODE_GPS_POINT enum. Load neutral position and start to point to Lat,Lon,Alt
	MAV_MOUNT_MODE_GPS_POINT MAV_MOUNT_MODE = 4
	// MAV_MOUNT_MODE_SYSID_TARGET enum. Gimbal tracks system with specified system ID
	MAV_MOUNT_MODE_SYSID_TARGET MAV_MOUNT_MODE = 5
	// MAV_MOUNT_MODE_HOME_LOCATION enum. Gimbal tracks home location
	MAV_MOUNT_MODE_HOME_LOCATION MAV_MOUNT_MODE = 6
)

func (MAV_MOUNT_MODE) Bitmask

func (e MAV_MOUNT_MODE) Bitmask() string

Bitmask return string representetion of intersects MAV_MOUNT_MODE enums

func (MAV_MOUNT_MODE) MarshalBinary

func (e MAV_MOUNT_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_MOUNT_MODE) String

func (e MAV_MOUNT_MODE) String() string

func (*MAV_MOUNT_MODE) UnmarshalBinary

func (e *MAV_MOUNT_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ODID_AUTH_TYPE

type MAV_ODID_AUTH_TYPE int

MAV_ODID_AUTH_TYPE type

const (
	// MAV_ODID_AUTH_TYPE_NONE enum. No authentication type is specified
	MAV_ODID_AUTH_TYPE_NONE MAV_ODID_AUTH_TYPE = 0
	// MAV_ODID_AUTH_TYPE_UAS_ID_SIGNATURE enum. Signature for the UAS (Unmanned Aircraft System) ID
	MAV_ODID_AUTH_TYPE_UAS_ID_SIGNATURE MAV_ODID_AUTH_TYPE = 1
	// MAV_ODID_AUTH_TYPE_OPERATOR_ID_SIGNATURE enum. Signature for the Operator ID
	MAV_ODID_AUTH_TYPE_OPERATOR_ID_SIGNATURE MAV_ODID_AUTH_TYPE = 2
	// MAV_ODID_AUTH_TYPE_MESSAGE_SET_SIGNATURE enum. Signature for the entire message set
	MAV_ODID_AUTH_TYPE_MESSAGE_SET_SIGNATURE MAV_ODID_AUTH_TYPE = 3
	// MAV_ODID_AUTH_TYPE_NETWORK_REMOTE_ID enum. Authentication is provided by Network Remote ID
	MAV_ODID_AUTH_TYPE_NETWORK_REMOTE_ID MAV_ODID_AUTH_TYPE = 4
)

func (MAV_ODID_AUTH_TYPE) Bitmask

func (e MAV_ODID_AUTH_TYPE) Bitmask() string

Bitmask return string representetion of intersects MAV_ODID_AUTH_TYPE enums

func (MAV_ODID_AUTH_TYPE) MarshalBinary

func (e MAV_ODID_AUTH_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ODID_AUTH_TYPE) String

func (e MAV_ODID_AUTH_TYPE) String() string

func (*MAV_ODID_AUTH_TYPE) UnmarshalBinary

func (e *MAV_ODID_AUTH_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ODID_CATEGORY_EU

type MAV_ODID_CATEGORY_EU int

MAV_ODID_CATEGORY_EU type

const (
	// MAV_ODID_CATEGORY_EU_UNDECLARED enum. The category for the UA, according to the EU specification, is undeclared
	MAV_ODID_CATEGORY_EU_UNDECLARED MAV_ODID_CATEGORY_EU = 0
	// MAV_ODID_CATEGORY_EU_OPEN enum. The category for the UA, according to the EU specification, is the Open category
	MAV_ODID_CATEGORY_EU_OPEN MAV_ODID_CATEGORY_EU = 1
	// MAV_ODID_CATEGORY_EU_SPECIFIC enum. The category for the UA, according to the EU specification, is the Specific category
	MAV_ODID_CATEGORY_EU_SPECIFIC MAV_ODID_CATEGORY_EU = 2
	// MAV_ODID_CATEGORY_EU_CERTIFIED enum. The category for the UA, according to the EU specification, is the Certified category
	MAV_ODID_CATEGORY_EU_CERTIFIED MAV_ODID_CATEGORY_EU = 3
)

func (MAV_ODID_CATEGORY_EU) Bitmask

func (e MAV_ODID_CATEGORY_EU) Bitmask() string

Bitmask return string representetion of intersects MAV_ODID_CATEGORY_EU enums

func (MAV_ODID_CATEGORY_EU) MarshalBinary

func (e MAV_ODID_CATEGORY_EU) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ODID_CATEGORY_EU) String

func (e MAV_ODID_CATEGORY_EU) String() string

func (*MAV_ODID_CATEGORY_EU) UnmarshalBinary

func (e *MAV_ODID_CATEGORY_EU) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ODID_CLASSIFICATION_TYPE

type MAV_ODID_CLASSIFICATION_TYPE int

MAV_ODID_CLASSIFICATION_TYPE type

const (
	// MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED enum. The classification type for the UA is undeclared
	MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED MAV_ODID_CLASSIFICATION_TYPE = 0
	// MAV_ODID_CLASSIFICATION_TYPE_EU enum. The classification type for the UA follows EU (European Union) specifications
	MAV_ODID_CLASSIFICATION_TYPE_EU MAV_ODID_CLASSIFICATION_TYPE = 1
)

func (MAV_ODID_CLASSIFICATION_TYPE) Bitmask

Bitmask return string representetion of intersects MAV_ODID_CLASSIFICATION_TYPE enums

func (MAV_ODID_CLASSIFICATION_TYPE) MarshalBinary

func (e MAV_ODID_CLASSIFICATION_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ODID_CLASSIFICATION_TYPE) String

func (*MAV_ODID_CLASSIFICATION_TYPE) UnmarshalBinary

func (e *MAV_ODID_CLASSIFICATION_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ODID_CLASS_EU

type MAV_ODID_CLASS_EU int

MAV_ODID_CLASS_EU type

const (
	// MAV_ODID_CLASS_EU_UNDECLARED enum. The class for the UA, according to the EU specification, is undeclared
	MAV_ODID_CLASS_EU_UNDECLARED MAV_ODID_CLASS_EU = 0
	// MAV_ODID_CLASS_EU_CLASS_0 enum. The class for the UA, according to the EU specification, is Class 0
	MAV_ODID_CLASS_EU_CLASS_0 MAV_ODID_CLASS_EU = 1
	// MAV_ODID_CLASS_EU_CLASS_1 enum. The class for the UA, according to the EU specification, is Class 1
	MAV_ODID_CLASS_EU_CLASS_1 MAV_ODID_CLASS_EU = 2
	// MAV_ODID_CLASS_EU_CLASS_2 enum. The class for the UA, according to the EU specification, is Class 2
	MAV_ODID_CLASS_EU_CLASS_2 MAV_ODID_CLASS_EU = 3
	// MAV_ODID_CLASS_EU_CLASS_3 enum. The class for the UA, according to the EU specification, is Class 3
	MAV_ODID_CLASS_EU_CLASS_3 MAV_ODID_CLASS_EU = 4
	// MAV_ODID_CLASS_EU_CLASS_4 enum. The class for the UA, according to the EU specification, is Class 4
	MAV_ODID_CLASS_EU_CLASS_4 MAV_ODID_CLASS_EU = 5
	// MAV_ODID_CLASS_EU_CLASS_5 enum. The class for the UA, according to the EU specification, is Class 5
	MAV_ODID_CLASS_EU_CLASS_5 MAV_ODID_CLASS_EU = 6
	// MAV_ODID_CLASS_EU_CLASS_6 enum. The class for the UA, according to the EU specification, is Class 6
	MAV_ODID_CLASS_EU_CLASS_6 MAV_ODID_CLASS_EU = 7
)

func (MAV_ODID_CLASS_EU) Bitmask

func (e MAV_ODID_CLASS_EU) Bitmask() string

Bitmask return string representetion of intersects MAV_ODID_CLASS_EU enums

func (MAV_ODID_CLASS_EU) MarshalBinary

func (e MAV_ODID_CLASS_EU) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ODID_CLASS_EU) String

func (e MAV_ODID_CLASS_EU) String() string

func (*MAV_ODID_CLASS_EU) UnmarshalBinary

func (e *MAV_ODID_CLASS_EU) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ODID_DESC_TYPE

type MAV_ODID_DESC_TYPE int

MAV_ODID_DESC_TYPE type

const (
	// MAV_ODID_DESC_TYPE_TEXT enum. Free-form text description of the purpose of the flight
	MAV_ODID_DESC_TYPE_TEXT MAV_ODID_DESC_TYPE = 0
)

func (MAV_ODID_DESC_TYPE) Bitmask

func (e MAV_ODID_DESC_TYPE) Bitmask() string

Bitmask return string representetion of intersects MAV_ODID_DESC_TYPE enums

func (MAV_ODID_DESC_TYPE) MarshalBinary

func (e MAV_ODID_DESC_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ODID_DESC_TYPE) String

func (e MAV_ODID_DESC_TYPE) String() string

func (*MAV_ODID_DESC_TYPE) UnmarshalBinary

func (e *MAV_ODID_DESC_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ODID_HEIGHT_REF

type MAV_ODID_HEIGHT_REF int

MAV_ODID_HEIGHT_REF type

const (
	// MAV_ODID_HEIGHT_REF_OVER_TAKEOFF enum. The height field is relative to the take-off location
	MAV_ODID_HEIGHT_REF_OVER_TAKEOFF MAV_ODID_HEIGHT_REF = 0
	// MAV_ODID_HEIGHT_REF_OVER_GROUND enum. The height field is relative to ground
	MAV_ODID_HEIGHT_REF_OVER_GROUND MAV_ODID_HEIGHT_REF = 1
)

func (MAV_ODID_HEIGHT_REF) Bitmask

func (e MAV_ODID_HEIGHT_REF) Bitmask() string

Bitmask return string representetion of intersects MAV_ODID_HEIGHT_REF enums

func (MAV_ODID_HEIGHT_REF) MarshalBinary

func (e MAV_ODID_HEIGHT_REF) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ODID_HEIGHT_REF) String

func (e MAV_ODID_HEIGHT_REF) String() string

func (*MAV_ODID_HEIGHT_REF) UnmarshalBinary

func (e *MAV_ODID_HEIGHT_REF) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ODID_HOR_ACC

type MAV_ODID_HOR_ACC int

MAV_ODID_HOR_ACC type

const (
	// MAV_ODID_HOR_ACC_UNKNOWN enum. The horizontal accuracy is unknown
	MAV_ODID_HOR_ACC_UNKNOWN MAV_ODID_HOR_ACC = 0
	// MAV_ODID_HOR_ACC_10NM enum. The horizontal accuracy is smaller than 10 Nautical Miles. 18.52 km
	MAV_ODID_HOR_ACC_10NM MAV_ODID_HOR_ACC = 1
	// MAV_ODID_HOR_ACC_4NM enum. The horizontal accuracy is smaller than 4 Nautical Miles. 7.408 km
	MAV_ODID_HOR_ACC_4NM MAV_ODID_HOR_ACC = 2
	// MAV_ODID_HOR_ACC_2NM enum. The horizontal accuracy is smaller than 2 Nautical Miles. 3.704 km
	MAV_ODID_HOR_ACC_2NM MAV_ODID_HOR_ACC = 3
	// MAV_ODID_HOR_ACC_1NM enum. The horizontal accuracy is smaller than 1 Nautical Miles. 1.852 km
	MAV_ODID_HOR_ACC_1NM MAV_ODID_HOR_ACC = 4
	// MAV_ODID_HOR_ACC_0_5NM enum. The horizontal accuracy is smaller than 0.5 Nautical Miles. 926 m
	MAV_ODID_HOR_ACC_0_5NM MAV_ODID_HOR_ACC = 5
	// MAV_ODID_HOR_ACC_0_3NM enum. The horizontal accuracy is smaller than 0.3 Nautical Miles. 555.6 m
	MAV_ODID_HOR_ACC_0_3NM MAV_ODID_HOR_ACC = 6
	// MAV_ODID_HOR_ACC_0_1NM enum. The horizontal accuracy is smaller than 0.1 Nautical Miles. 185.2 m
	MAV_ODID_HOR_ACC_0_1NM MAV_ODID_HOR_ACC = 7
	// MAV_ODID_HOR_ACC_0_05NM enum. The horizontal accuracy is smaller than 0.05 Nautical Miles. 92.6 m
	MAV_ODID_HOR_ACC_0_05NM MAV_ODID_HOR_ACC = 8
	// MAV_ODID_HOR_ACC_30_METER enum. The horizontal accuracy is smaller than 30 meter
	MAV_ODID_HOR_ACC_30_METER MAV_ODID_HOR_ACC = 9
	// MAV_ODID_HOR_ACC_10_METER enum. The horizontal accuracy is smaller than 10 meter
	MAV_ODID_HOR_ACC_10_METER MAV_ODID_HOR_ACC = 10
	// MAV_ODID_HOR_ACC_3_METER enum. The horizontal accuracy is smaller than 3 meter
	MAV_ODID_HOR_ACC_3_METER MAV_ODID_HOR_ACC = 11
	// MAV_ODID_HOR_ACC_1_METER enum. The horizontal accuracy is smaller than 1 meter
	MAV_ODID_HOR_ACC_1_METER MAV_ODID_HOR_ACC = 12
)

func (MAV_ODID_HOR_ACC) Bitmask

func (e MAV_ODID_HOR_ACC) Bitmask() string

Bitmask return string representetion of intersects MAV_ODID_HOR_ACC enums

func (MAV_ODID_HOR_ACC) MarshalBinary

func (e MAV_ODID_HOR_ACC) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ODID_HOR_ACC) String

func (e MAV_ODID_HOR_ACC) String() string

func (*MAV_ODID_HOR_ACC) UnmarshalBinary

func (e *MAV_ODID_HOR_ACC) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ODID_ID_TYPE

type MAV_ODID_ID_TYPE int

MAV_ODID_ID_TYPE type

const (
	// MAV_ODID_ID_TYPE_NONE enum. No type defined
	MAV_ODID_ID_TYPE_NONE MAV_ODID_ID_TYPE = 0
	// MAV_ODID_ID_TYPE_SERIAL_NUMBER enum. Manufacturer Serial Number (ANSI/CTA-2063 format)
	MAV_ODID_ID_TYPE_SERIAL_NUMBER MAV_ODID_ID_TYPE = 1
	// MAV_ODID_ID_TYPE_CAA_REGISTRATION_ID enum. CAA (Civil Aviation Authority) registered ID. Format: [ICAO Country Code].[CAA Assigned ID]
	MAV_ODID_ID_TYPE_CAA_REGISTRATION_ID MAV_ODID_ID_TYPE = 2
	// MAV_ODID_ID_TYPE_UTM_ASSIGNED_UUID enum. UTM (Unmanned Traffic Management) assigned UUID (RFC4122)
	MAV_ODID_ID_TYPE_UTM_ASSIGNED_UUID MAV_ODID_ID_TYPE = 3
)

func (MAV_ODID_ID_TYPE) Bitmask

func (e MAV_ODID_ID_TYPE) Bitmask() string

Bitmask return string representetion of intersects MAV_ODID_ID_TYPE enums

func (MAV_ODID_ID_TYPE) MarshalBinary

func (e MAV_ODID_ID_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ODID_ID_TYPE) String

func (e MAV_ODID_ID_TYPE) String() string

func (*MAV_ODID_ID_TYPE) UnmarshalBinary

func (e *MAV_ODID_ID_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ODID_OPERATOR_ID_TYPE

type MAV_ODID_OPERATOR_ID_TYPE int

MAV_ODID_OPERATOR_ID_TYPE type

const (
	// MAV_ODID_OPERATOR_ID_TYPE_CAA enum. CAA (Civil Aviation Authority) registered operator ID
	MAV_ODID_OPERATOR_ID_TYPE_CAA MAV_ODID_OPERATOR_ID_TYPE = 0
)

func (MAV_ODID_OPERATOR_ID_TYPE) Bitmask

func (e MAV_ODID_OPERATOR_ID_TYPE) Bitmask() string

Bitmask return string representetion of intersects MAV_ODID_OPERATOR_ID_TYPE enums

func (MAV_ODID_OPERATOR_ID_TYPE) MarshalBinary

func (e MAV_ODID_OPERATOR_ID_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ODID_OPERATOR_ID_TYPE) String

func (e MAV_ODID_OPERATOR_ID_TYPE) String() string

func (*MAV_ODID_OPERATOR_ID_TYPE) UnmarshalBinary

func (e *MAV_ODID_OPERATOR_ID_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ODID_OPERATOR_LOCATION_TYPE

type MAV_ODID_OPERATOR_LOCATION_TYPE int

MAV_ODID_OPERATOR_LOCATION_TYPE type

const (
	// MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF enum. The location of the operator is the same as the take-off location
	MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF MAV_ODID_OPERATOR_LOCATION_TYPE = 0
	// MAV_ODID_OPERATOR_LOCATION_TYPE_LIVE_GNSS enum. The location of the operator is based on live GNSS data
	MAV_ODID_OPERATOR_LOCATION_TYPE_LIVE_GNSS MAV_ODID_OPERATOR_LOCATION_TYPE = 1
	// MAV_ODID_OPERATOR_LOCATION_TYPE_FIXED enum. The location of the operator is a fixed location
	MAV_ODID_OPERATOR_LOCATION_TYPE_FIXED MAV_ODID_OPERATOR_LOCATION_TYPE = 2
)

func (MAV_ODID_OPERATOR_LOCATION_TYPE) Bitmask

Bitmask return string representetion of intersects MAV_ODID_OPERATOR_LOCATION_TYPE enums

func (MAV_ODID_OPERATOR_LOCATION_TYPE) MarshalBinary

func (e MAV_ODID_OPERATOR_LOCATION_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ODID_OPERATOR_LOCATION_TYPE) String

func (*MAV_ODID_OPERATOR_LOCATION_TYPE) UnmarshalBinary

func (e *MAV_ODID_OPERATOR_LOCATION_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ODID_SPEED_ACC

type MAV_ODID_SPEED_ACC int

MAV_ODID_SPEED_ACC type

const (
	// MAV_ODID_SPEED_ACC_UNKNOWN enum. The speed accuracy is unknown
	MAV_ODID_SPEED_ACC_UNKNOWN MAV_ODID_SPEED_ACC = 0
	// MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND enum. The speed accuracy is smaller than 10 meters per second
	MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND MAV_ODID_SPEED_ACC = 1
	// MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND enum. The speed accuracy is smaller than 3 meters per second
	MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND MAV_ODID_SPEED_ACC = 2
	// MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND enum. The speed accuracy is smaller than 1 meters per second
	MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND MAV_ODID_SPEED_ACC = 3
	// MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND enum. The speed accuracy is smaller than 0.3 meters per second
	MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND MAV_ODID_SPEED_ACC = 4
)

func (MAV_ODID_SPEED_ACC) Bitmask

func (e MAV_ODID_SPEED_ACC) Bitmask() string

Bitmask return string representetion of intersects MAV_ODID_SPEED_ACC enums

func (MAV_ODID_SPEED_ACC) MarshalBinary

func (e MAV_ODID_SPEED_ACC) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ODID_SPEED_ACC) String

func (e MAV_ODID_SPEED_ACC) String() string

func (*MAV_ODID_SPEED_ACC) UnmarshalBinary

func (e *MAV_ODID_SPEED_ACC) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ODID_STATUS

type MAV_ODID_STATUS int

MAV_ODID_STATUS type

const (
	// MAV_ODID_STATUS_UNDECLARED enum. The status of the (UA) Unmanned Aircraft is undefined
	MAV_ODID_STATUS_UNDECLARED MAV_ODID_STATUS = 0
	// MAV_ODID_STATUS_GROUND enum. The UA is on the ground
	MAV_ODID_STATUS_GROUND MAV_ODID_STATUS = 1
	// MAV_ODID_STATUS_AIRBORNE enum. The UA is in the air
	MAV_ODID_STATUS_AIRBORNE MAV_ODID_STATUS = 2
	// MAV_ODID_STATUS_EMERGENCY enum. The UA is having an emergency
	MAV_ODID_STATUS_EMERGENCY MAV_ODID_STATUS = 3
)

func (MAV_ODID_STATUS) Bitmask

func (e MAV_ODID_STATUS) Bitmask() string

Bitmask return string representetion of intersects MAV_ODID_STATUS enums

func (MAV_ODID_STATUS) MarshalBinary

func (e MAV_ODID_STATUS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ODID_STATUS) String

func (e MAV_ODID_STATUS) String() string

func (*MAV_ODID_STATUS) UnmarshalBinary

func (e *MAV_ODID_STATUS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ODID_TIME_ACC

type MAV_ODID_TIME_ACC int

MAV_ODID_TIME_ACC type

const (
	// MAV_ODID_TIME_ACC_UNKNOWN enum. The timestamp accuracy is unknown
	MAV_ODID_TIME_ACC_UNKNOWN MAV_ODID_TIME_ACC = 0
	// MAV_ODID_TIME_ACC_0_1_SECOND enum. The timestamp accuracy is smaller than or equal to 0.1 second
	MAV_ODID_TIME_ACC_0_1_SECOND MAV_ODID_TIME_ACC = 1
	// MAV_ODID_TIME_ACC_0_2_SECOND enum. The timestamp accuracy is smaller than or equal to 0.2 second
	MAV_ODID_TIME_ACC_0_2_SECOND MAV_ODID_TIME_ACC = 2
	// MAV_ODID_TIME_ACC_0_3_SECOND enum. The timestamp accuracy is smaller than or equal to 0.3 second
	MAV_ODID_TIME_ACC_0_3_SECOND MAV_ODID_TIME_ACC = 3
	// MAV_ODID_TIME_ACC_0_4_SECOND enum. The timestamp accuracy is smaller than or equal to 0.4 second
	MAV_ODID_TIME_ACC_0_4_SECOND MAV_ODID_TIME_ACC = 4
	// MAV_ODID_TIME_ACC_0_5_SECOND enum. The timestamp accuracy is smaller than or equal to 0.5 second
	MAV_ODID_TIME_ACC_0_5_SECOND MAV_ODID_TIME_ACC = 5
	// MAV_ODID_TIME_ACC_0_6_SECOND enum. The timestamp accuracy is smaller than or equal to 0.6 second
	MAV_ODID_TIME_ACC_0_6_SECOND MAV_ODID_TIME_ACC = 6
	// MAV_ODID_TIME_ACC_0_7_SECOND enum. The timestamp accuracy is smaller than or equal to 0.7 second
	MAV_ODID_TIME_ACC_0_7_SECOND MAV_ODID_TIME_ACC = 7
	// MAV_ODID_TIME_ACC_0_8_SECOND enum. The timestamp accuracy is smaller than or equal to 0.8 second
	MAV_ODID_TIME_ACC_0_8_SECOND MAV_ODID_TIME_ACC = 8
	// MAV_ODID_TIME_ACC_0_9_SECOND enum. The timestamp accuracy is smaller than or equal to 0.9 second
	MAV_ODID_TIME_ACC_0_9_SECOND MAV_ODID_TIME_ACC = 9
	// MAV_ODID_TIME_ACC_1_0_SECOND enum. The timestamp accuracy is smaller than or equal to 1.0 second
	MAV_ODID_TIME_ACC_1_0_SECOND MAV_ODID_TIME_ACC = 10
	// MAV_ODID_TIME_ACC_1_1_SECOND enum. The timestamp accuracy is smaller than or equal to 1.1 second
	MAV_ODID_TIME_ACC_1_1_SECOND MAV_ODID_TIME_ACC = 11
	// MAV_ODID_TIME_ACC_1_2_SECOND enum. The timestamp accuracy is smaller than or equal to 1.2 second
	MAV_ODID_TIME_ACC_1_2_SECOND MAV_ODID_TIME_ACC = 12
	// MAV_ODID_TIME_ACC_1_3_SECOND enum. The timestamp accuracy is smaller than or equal to 1.3 second
	MAV_ODID_TIME_ACC_1_3_SECOND MAV_ODID_TIME_ACC = 13
	// MAV_ODID_TIME_ACC_1_4_SECOND enum. The timestamp accuracy is smaller than or equal to 1.4 second
	MAV_ODID_TIME_ACC_1_4_SECOND MAV_ODID_TIME_ACC = 14
	// MAV_ODID_TIME_ACC_1_5_SECOND enum. The timestamp accuracy is smaller than or equal to 1.5 second
	MAV_ODID_TIME_ACC_1_5_SECOND MAV_ODID_TIME_ACC = 15
)

func (MAV_ODID_TIME_ACC) Bitmask

func (e MAV_ODID_TIME_ACC) Bitmask() string

Bitmask return string representetion of intersects MAV_ODID_TIME_ACC enums

func (MAV_ODID_TIME_ACC) MarshalBinary

func (e MAV_ODID_TIME_ACC) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ODID_TIME_ACC) String

func (e MAV_ODID_TIME_ACC) String() string

func (*MAV_ODID_TIME_ACC) UnmarshalBinary

func (e *MAV_ODID_TIME_ACC) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ODID_UA_TYPE

type MAV_ODID_UA_TYPE int

MAV_ODID_UA_TYPE type

const (
	// MAV_ODID_UA_TYPE_NONE enum. No UA (Unmanned Aircraft) type defined
	MAV_ODID_UA_TYPE_NONE MAV_ODID_UA_TYPE = 0
	// MAV_ODID_UA_TYPE_AEROPLANE enum. Aeroplane/Airplane. Fixed wing
	MAV_ODID_UA_TYPE_AEROPLANE MAV_ODID_UA_TYPE = 1
	// MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR enum. Helicopter or multirotor
	MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR MAV_ODID_UA_TYPE = 2
	// MAV_ODID_UA_TYPE_GYROPLANE enum. Gyroplane
	MAV_ODID_UA_TYPE_GYROPLANE MAV_ODID_UA_TYPE = 3
	// MAV_ODID_UA_TYPE_HYBRID_LIFT enum. VTOL (Vertical Take-Off and Landing). Fixed wing aircraft that can take off vertically
	MAV_ODID_UA_TYPE_HYBRID_LIFT MAV_ODID_UA_TYPE = 4
	// MAV_ODID_UA_TYPE_ORNITHOPTER enum. Ornithopter
	MAV_ODID_UA_TYPE_ORNITHOPTER MAV_ODID_UA_TYPE = 5
	// MAV_ODID_UA_TYPE_GLIDER enum. Glider
	MAV_ODID_UA_TYPE_GLIDER MAV_ODID_UA_TYPE = 6
	// MAV_ODID_UA_TYPE_KITE enum. Kite
	MAV_ODID_UA_TYPE_KITE MAV_ODID_UA_TYPE = 7
	// MAV_ODID_UA_TYPE_FREE_BALLOON enum. Free Balloon
	MAV_ODID_UA_TYPE_FREE_BALLOON MAV_ODID_UA_TYPE = 8
	// MAV_ODID_UA_TYPE_CAPTIVE_BALLOON enum. Captive Balloon
	MAV_ODID_UA_TYPE_CAPTIVE_BALLOON MAV_ODID_UA_TYPE = 9
	// MAV_ODID_UA_TYPE_AIRSHIP enum. Airship. E.g. a blimp
	MAV_ODID_UA_TYPE_AIRSHIP MAV_ODID_UA_TYPE = 10
	// MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE enum. Free Fall/Parachute (unpowered)
	MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE MAV_ODID_UA_TYPE = 11
	// MAV_ODID_UA_TYPE_ROCKET enum. Rocket
	MAV_ODID_UA_TYPE_ROCKET MAV_ODID_UA_TYPE = 12
	// MAV_ODID_UA_TYPE_TETHERED_POWERED_AIRCRAFT enum. Tethered powered aircraft
	MAV_ODID_UA_TYPE_TETHERED_POWERED_AIRCRAFT MAV_ODID_UA_TYPE = 13
	// MAV_ODID_UA_TYPE_GROUND_OBSTACLE enum. Ground Obstacle
	MAV_ODID_UA_TYPE_GROUND_OBSTACLE MAV_ODID_UA_TYPE = 14
	// MAV_ODID_UA_TYPE_OTHER enum. Other type of aircraft not listed earlier
	MAV_ODID_UA_TYPE_OTHER MAV_ODID_UA_TYPE = 15
)

func (MAV_ODID_UA_TYPE) Bitmask

func (e MAV_ODID_UA_TYPE) Bitmask() string

Bitmask return string representetion of intersects MAV_ODID_UA_TYPE enums

func (MAV_ODID_UA_TYPE) MarshalBinary

func (e MAV_ODID_UA_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ODID_UA_TYPE) String

func (e MAV_ODID_UA_TYPE) String() string

func (*MAV_ODID_UA_TYPE) UnmarshalBinary

func (e *MAV_ODID_UA_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ODID_VER_ACC

type MAV_ODID_VER_ACC int

MAV_ODID_VER_ACC type

const (
	// MAV_ODID_VER_ACC_UNKNOWN enum. The vertical accuracy is unknown
	MAV_ODID_VER_ACC_UNKNOWN MAV_ODID_VER_ACC = 0
	// MAV_ODID_VER_ACC_150_METER enum. The vertical accuracy is smaller than 150 meter
	MAV_ODID_VER_ACC_150_METER MAV_ODID_VER_ACC = 1
	// MAV_ODID_VER_ACC_45_METER enum. The vertical accuracy is smaller than 45 meter
	MAV_ODID_VER_ACC_45_METER MAV_ODID_VER_ACC = 2
	// MAV_ODID_VER_ACC_25_METER enum. The vertical accuracy is smaller than 25 meter
	MAV_ODID_VER_ACC_25_METER MAV_ODID_VER_ACC = 3
	// MAV_ODID_VER_ACC_10_METER enum. The vertical accuracy is smaller than 10 meter
	MAV_ODID_VER_ACC_10_METER MAV_ODID_VER_ACC = 4
	// MAV_ODID_VER_ACC_3_METER enum. The vertical accuracy is smaller than 3 meter
	MAV_ODID_VER_ACC_3_METER MAV_ODID_VER_ACC = 5
	// MAV_ODID_VER_ACC_1_METER enum. The vertical accuracy is smaller than 1 meter
	MAV_ODID_VER_ACC_1_METER MAV_ODID_VER_ACC = 6
)

func (MAV_ODID_VER_ACC) Bitmask

func (e MAV_ODID_VER_ACC) Bitmask() string

Bitmask return string representetion of intersects MAV_ODID_VER_ACC enums

func (MAV_ODID_VER_ACC) MarshalBinary

func (e MAV_ODID_VER_ACC) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ODID_VER_ACC) String

func (e MAV_ODID_VER_ACC) String() string

func (*MAV_ODID_VER_ACC) UnmarshalBinary

func (e *MAV_ODID_VER_ACC) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_PARAM_EXT_TYPE

type MAV_PARAM_EXT_TYPE int

MAV_PARAM_EXT_TYPE type. Specifies the datatype of a MAVLink extended parameter.

const (
	// MAV_PARAM_EXT_TYPE_UINT8 enum. 8-bit unsigned integer
	MAV_PARAM_EXT_TYPE_UINT8 MAV_PARAM_EXT_TYPE = 1
	// MAV_PARAM_EXT_TYPE_INT8 enum. 8-bit signed integer
	MAV_PARAM_EXT_TYPE_INT8 MAV_PARAM_EXT_TYPE = 2
	// MAV_PARAM_EXT_TYPE_UINT16 enum. 16-bit unsigned integer
	MAV_PARAM_EXT_TYPE_UINT16 MAV_PARAM_EXT_TYPE = 3
	// MAV_PARAM_EXT_TYPE_INT16 enum. 16-bit signed integer
	MAV_PARAM_EXT_TYPE_INT16 MAV_PARAM_EXT_TYPE = 4
	// MAV_PARAM_EXT_TYPE_UINT32 enum. 32-bit unsigned integer
	MAV_PARAM_EXT_TYPE_UINT32 MAV_PARAM_EXT_TYPE = 5
	// MAV_PARAM_EXT_TYPE_INT32 enum. 32-bit signed integer
	MAV_PARAM_EXT_TYPE_INT32 MAV_PARAM_EXT_TYPE = 6
	// MAV_PARAM_EXT_TYPE_UINT64 enum. 64-bit unsigned integer
	MAV_PARAM_EXT_TYPE_UINT64 MAV_PARAM_EXT_TYPE = 7
	// MAV_PARAM_EXT_TYPE_INT64 enum. 64-bit signed integer
	MAV_PARAM_EXT_TYPE_INT64 MAV_PARAM_EXT_TYPE = 8
	// MAV_PARAM_EXT_TYPE_REAL32 enum. 32-bit floating-point
	MAV_PARAM_EXT_TYPE_REAL32 MAV_PARAM_EXT_TYPE = 9
	// MAV_PARAM_EXT_TYPE_REAL64 enum. 64-bit floating-point
	MAV_PARAM_EXT_TYPE_REAL64 MAV_PARAM_EXT_TYPE = 10
	// MAV_PARAM_EXT_TYPE_CUSTOM enum. Custom Type
	MAV_PARAM_EXT_TYPE_CUSTOM MAV_PARAM_EXT_TYPE = 11
)

func (MAV_PARAM_EXT_TYPE) Bitmask

func (e MAV_PARAM_EXT_TYPE) Bitmask() string

Bitmask return string representetion of intersects MAV_PARAM_EXT_TYPE enums

func (MAV_PARAM_EXT_TYPE) MarshalBinary

func (e MAV_PARAM_EXT_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_PARAM_EXT_TYPE) String

func (e MAV_PARAM_EXT_TYPE) String() string

func (*MAV_PARAM_EXT_TYPE) UnmarshalBinary

func (e *MAV_PARAM_EXT_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_PARAM_TYPE

type MAV_PARAM_TYPE int

MAV_PARAM_TYPE type. Specifies the datatype of a MAVLink parameter.

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

func (MAV_PARAM_TYPE) Bitmask

func (e MAV_PARAM_TYPE) Bitmask() string

Bitmask return string representetion of intersects MAV_PARAM_TYPE enums

func (MAV_PARAM_TYPE) MarshalBinary

func (e MAV_PARAM_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_PARAM_TYPE) String

func (e MAV_PARAM_TYPE) String() string

func (*MAV_PARAM_TYPE) UnmarshalBinary

func (e *MAV_PARAM_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_POWER_STATUS

type MAV_POWER_STATUS int

MAV_POWER_STATUS type. Power supply status flags (bitmask)

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

func (MAV_POWER_STATUS) Bitmask

func (e MAV_POWER_STATUS) Bitmask() string

Bitmask return string representetion of intersects MAV_POWER_STATUS enums

func (MAV_POWER_STATUS) MarshalBinary

func (e MAV_POWER_STATUS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_POWER_STATUS) String

func (e MAV_POWER_STATUS) String() string

func (*MAV_POWER_STATUS) UnmarshalBinary

func (e *MAV_POWER_STATUS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_PROTOCOL_CAPABILITY

type MAV_PROTOCOL_CAPABILITY int

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

const (
	// MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT enum. Autopilot supports MISSION float message type
	MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT MAV_PROTOCOL_CAPABILITY = 1
	// MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT enum. Autopilot supports the new param float message type
	MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT MAV_PROTOCOL_CAPABILITY = 2
	// MAV_PROTOCOL_CAPABILITY_MISSION_INT enum. Autopilot supports MISSION_ITEM_INT scaled integer message type
	MAV_PROTOCOL_CAPABILITY_MISSION_INT MAV_PROTOCOL_CAPABILITY = 4
	// MAV_PROTOCOL_CAPABILITY_COMMAND_INT enum. Autopilot supports COMMAND_INT scaled integer message type
	MAV_PROTOCOL_CAPABILITY_COMMAND_INT MAV_PROTOCOL_CAPABILITY = 8
	// MAV_PROTOCOL_CAPABILITY_PARAM_UNION enum. Autopilot supports the new param union message type
	MAV_PROTOCOL_CAPABILITY_PARAM_UNION MAV_PROTOCOL_CAPABILITY = 16
	// MAV_PROTOCOL_CAPABILITY_FTP enum. Autopilot supports the new FILE_TRANSFER_PROTOCOL message type
	MAV_PROTOCOL_CAPABILITY_FTP MAV_PROTOCOL_CAPABILITY = 32
	// MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET enum. Autopilot supports commanding attitude offboard
	MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET MAV_PROTOCOL_CAPABILITY = 64
	// MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED enum. Autopilot supports commanding position and velocity targets in local NED frame
	MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED MAV_PROTOCOL_CAPABILITY = 128
	// MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT enum. Autopilot supports commanding position and velocity targets in global scaled integers
	MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT MAV_PROTOCOL_CAPABILITY = 256
	// MAV_PROTOCOL_CAPABILITY_TERRAIN enum. Autopilot supports terrain protocol / data handling
	MAV_PROTOCOL_CAPABILITY_TERRAIN MAV_PROTOCOL_CAPABILITY = 512
	// MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET enum. Autopilot supports direct actuator control
	MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGET MAV_PROTOCOL_CAPABILITY = 1024
	// MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION enum. Autopilot supports the flight termination command
	MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION MAV_PROTOCOL_CAPABILITY = 2048
	// MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION enum. Autopilot supports onboard compass calibration
	MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION MAV_PROTOCOL_CAPABILITY = 4096
	// MAV_PROTOCOL_CAPABILITY_MAVLINK2 enum. Autopilot supports MAVLink version 2
	MAV_PROTOCOL_CAPABILITY_MAVLINK2 MAV_PROTOCOL_CAPABILITY = 8192
	// MAV_PROTOCOL_CAPABILITY_MISSION_FENCE enum. Autopilot supports mission fence protocol
	MAV_PROTOCOL_CAPABILITY_MISSION_FENCE MAV_PROTOCOL_CAPABILITY = 16384
	// MAV_PROTOCOL_CAPABILITY_MISSION_RALLY enum. Autopilot supports mission rally point protocol
	MAV_PROTOCOL_CAPABILITY_MISSION_RALLY MAV_PROTOCOL_CAPABILITY = 32768
	// MAV_PROTOCOL_CAPABILITY_FLIGHT_INFORMATION enum. Autopilot supports the flight information protocol
	MAV_PROTOCOL_CAPABILITY_FLIGHT_INFORMATION MAV_PROTOCOL_CAPABILITY = 65536
)

func (MAV_PROTOCOL_CAPABILITY) Bitmask

func (e MAV_PROTOCOL_CAPABILITY) Bitmask() string

Bitmask return string representetion of intersects MAV_PROTOCOL_CAPABILITY enums

func (MAV_PROTOCOL_CAPABILITY) MarshalBinary

func (e MAV_PROTOCOL_CAPABILITY) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_PROTOCOL_CAPABILITY) String

func (e MAV_PROTOCOL_CAPABILITY) String() string

func (*MAV_PROTOCOL_CAPABILITY) UnmarshalBinary

func (e *MAV_PROTOCOL_CAPABILITY) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_QSHOT_MODE added in v1.3.0

type MAV_QSHOT_MODE int

MAV_QSHOT_MODE type. Enumeration of possible shot modes.

const (
	// MAV_QSHOT_MODE_UNDEFINED enum. Undefined shot mode. Can be used to determine if qshots should be used or not
	MAV_QSHOT_MODE_UNDEFINED MAV_QSHOT_MODE = 0
	// MAV_QSHOT_MODE_DEFAULT enum. Start normal gimbal operation. Is usally used to return back from a shot
	MAV_QSHOT_MODE_DEFAULT MAV_QSHOT_MODE = 1
	// MAV_QSHOT_MODE_GIMBAL_RETRACT enum. Load and keep safe gimbal position and stop stabilization
	MAV_QSHOT_MODE_GIMBAL_RETRACT MAV_QSHOT_MODE = 2
	// MAV_QSHOT_MODE_GIMBAL_NEUTRAL enum. Load neutral gimbal position and keep it while stabilizing
	MAV_QSHOT_MODE_GIMBAL_NEUTRAL MAV_QSHOT_MODE = 3
	// MAV_QSHOT_MODE_GIMBAL_MISSION enum. Start mission with gimbal control
	MAV_QSHOT_MODE_GIMBAL_MISSION MAV_QSHOT_MODE = 4
	// MAV_QSHOT_MODE_GIMBAL_RC_CONTROL enum. Start RC gimbal control
	MAV_QSHOT_MODE_GIMBAL_RC_CONTROL MAV_QSHOT_MODE = 5
	// MAV_QSHOT_MODE_POI_TARGETING enum. Start gimbal tracking the point specified by Lat, Lon, Alt
	MAV_QSHOT_MODE_POI_TARGETING MAV_QSHOT_MODE = 6
	// MAV_QSHOT_MODE_SYSID_TARGETING enum. Start gimbal tracking the system with specified system ID
	MAV_QSHOT_MODE_SYSID_TARGETING MAV_QSHOT_MODE = 7
	// MAV_QSHOT_MODE_CABLECAM_2POINT enum. Start 2-point cable cam quick shot
	MAV_QSHOT_MODE_CABLECAM_2POINT MAV_QSHOT_MODE = 8
)

func (MAV_QSHOT_MODE) Bitmask added in v1.3.0

func (e MAV_QSHOT_MODE) Bitmask() string

Bitmask return string representetion of intersects MAV_QSHOT_MODE enums

func (MAV_QSHOT_MODE) MarshalBinary added in v1.3.0

func (e MAV_QSHOT_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_QSHOT_MODE) String added in v1.3.0

func (e MAV_QSHOT_MODE) String() string

func (*MAV_QSHOT_MODE) UnmarshalBinary added in v1.3.0

func (e *MAV_QSHOT_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS

type MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS int

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

const (
	// MAV_REMOTE_LOG_DATA_BLOCK_STOP enum. UAV to stop sending DataFlash blocks
	MAV_REMOTE_LOG_DATA_BLOCK_STOP MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS = 2147483645
	// MAV_REMOTE_LOG_DATA_BLOCK_START enum. UAV to start sending DataFlash blocks
	MAV_REMOTE_LOG_DATA_BLOCK_START MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS = 2147483646
)

func (MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS) Bitmask

Bitmask return string representetion of intersects MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS enums

func (MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS) MarshalBinary

func (e MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS) String

func (*MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS) UnmarshalBinary

func (e *MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_REMOTE_LOG_DATA_BLOCK_STATUSES

type MAV_REMOTE_LOG_DATA_BLOCK_STATUSES int

MAV_REMOTE_LOG_DATA_BLOCK_STATUSES type. Possible remote log data block statuses.

const (
	// MAV_REMOTE_LOG_DATA_BLOCK_NACK enum. This block has NOT been received
	MAV_REMOTE_LOG_DATA_BLOCK_NACK MAV_REMOTE_LOG_DATA_BLOCK_STATUSES = 0
	// MAV_REMOTE_LOG_DATA_BLOCK_ACK enum. This block has been received
	MAV_REMOTE_LOG_DATA_BLOCK_ACK MAV_REMOTE_LOG_DATA_BLOCK_STATUSES = 1
)

func (MAV_REMOTE_LOG_DATA_BLOCK_STATUSES) Bitmask

Bitmask return string representetion of intersects MAV_REMOTE_LOG_DATA_BLOCK_STATUSES enums

func (MAV_REMOTE_LOG_DATA_BLOCK_STATUSES) MarshalBinary

func (e MAV_REMOTE_LOG_DATA_BLOCK_STATUSES) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_REMOTE_LOG_DATA_BLOCK_STATUSES) String

func (*MAV_REMOTE_LOG_DATA_BLOCK_STATUSES) UnmarshalBinary

func (e *MAV_REMOTE_LOG_DATA_BLOCK_STATUSES) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_RESULT

type MAV_RESULT int

MAV_RESULT type. Result from a MAVLink command (MAV_CMD)

const (
	// MAV_RESULT_ACCEPTED enum. Command is valid (is supported and has valid parameters), and was executed
	MAV_RESULT_ACCEPTED MAV_RESULT = 0
	// MAV_RESULT_TEMPORARILY_REJECTED enum. Command is valid, but cannot be executed at this time. This is used to indicate a problem that should be fixed just by waiting (e.g. a state machine is busy, can't arm because have not got GPS lock, etc.). Retrying later should work
	MAV_RESULT_TEMPORARILY_REJECTED MAV_RESULT = 1
	// MAV_RESULT_DENIED enum. Command is invalid (is supported but has invalid parameters). Retrying same command and parameters will not work
	MAV_RESULT_DENIED MAV_RESULT = 2
	// MAV_RESULT_UNSUPPORTED enum. Command is not supported (unknown)
	MAV_RESULT_UNSUPPORTED MAV_RESULT = 3
	// MAV_RESULT_FAILED enum. Command is valid, but execution has failed. This is used to indicate any non-temporary or unexpected problem, i.e. any problem that must be fixed before the command can succeed/be retried. For example, attempting to write a file when out of memory, attempting to arm when sensors are not calibrated, etc
	MAV_RESULT_FAILED MAV_RESULT = 4
	// MAV_RESULT_IN_PROGRESS enum. Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation
	MAV_RESULT_IN_PROGRESS MAV_RESULT = 5
	// MAV_RESULT_CANCELLED enum. Command has been cancelled (as a result of receiving a COMMAND_CANCEL message)
	MAV_RESULT_CANCELLED MAV_RESULT = 6
)

func (MAV_RESULT) Bitmask

func (e MAV_RESULT) Bitmask() string

Bitmask return string representetion of intersects MAV_RESULT enums

func (MAV_RESULT) MarshalBinary

func (e MAV_RESULT) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_RESULT) String

func (e MAV_RESULT) String() string

func (*MAV_RESULT) UnmarshalBinary

func (e *MAV_RESULT) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_ROI

type MAV_ROI int

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

const (
	// MAV_ROI_NONE enum. No region of interest
	MAV_ROI_NONE MAV_ROI = 0
	// MAV_ROI_WPNEXT enum. Point toward next waypoint, with optional pitch/roll/yaw offset
	MAV_ROI_WPNEXT MAV_ROI = 1
	// MAV_ROI_WPINDEX enum. Point toward given waypoint
	MAV_ROI_WPINDEX MAV_ROI = 2
	// MAV_ROI_LOCATION enum. Point toward fixed location
	MAV_ROI_LOCATION MAV_ROI = 3
	// MAV_ROI_TARGET enum. Point toward of given id
	MAV_ROI_TARGET MAV_ROI = 4
)

func (MAV_ROI) Bitmask

func (e MAV_ROI) Bitmask() string

Bitmask return string representetion of intersects MAV_ROI enums

func (MAV_ROI) MarshalBinary

func (e MAV_ROI) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_ROI) String

func (e MAV_ROI) String() string

func (*MAV_ROI) UnmarshalBinary

func (e *MAV_ROI) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_SENSOR_ORIENTATION

type MAV_SENSOR_ORIENTATION int

MAV_SENSOR_ORIENTATION type. Enumeration of sensor orientation, according to its rotations

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

func (MAV_SENSOR_ORIENTATION) Bitmask

func (e MAV_SENSOR_ORIENTATION) Bitmask() string

Bitmask return string representetion of intersects MAV_SENSOR_ORIENTATION enums

func (MAV_SENSOR_ORIENTATION) MarshalBinary

func (e MAV_SENSOR_ORIENTATION) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_SENSOR_ORIENTATION) String

func (e MAV_SENSOR_ORIENTATION) String() string

func (*MAV_SENSOR_ORIENTATION) UnmarshalBinary

func (e *MAV_SENSOR_ORIENTATION) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_SEVERITY

type MAV_SEVERITY int

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

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

func (MAV_SEVERITY) Bitmask

func (e MAV_SEVERITY) Bitmask() string

Bitmask return string representetion of intersects MAV_SEVERITY enums

func (MAV_SEVERITY) MarshalBinary

func (e MAV_SEVERITY) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_SEVERITY) String

func (e MAV_SEVERITY) String() string

func (*MAV_SEVERITY) UnmarshalBinary

func (e *MAV_SEVERITY) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_STATE

type MAV_STATE int

MAV_STATE type

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

func (MAV_STATE) Bitmask

func (e MAV_STATE) Bitmask() string

Bitmask return string representetion of intersects MAV_STATE enums

func (MAV_STATE) MarshalBinary

func (e MAV_STATE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_STATE) String

func (e MAV_STATE) String() string

func (*MAV_STATE) UnmarshalBinary

func (e *MAV_STATE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_STORM32_GIMBAL_ACTION added in v1.3.0

type MAV_STORM32_GIMBAL_ACTION int

MAV_STORM32_GIMBAL_ACTION type. Gimbal actions.

const (
	// MAV_STORM32_GIMBAL_ACTION_RECENTER enum. Trigger the gimbal device to recenter the gimbal
	MAV_STORM32_GIMBAL_ACTION_RECENTER MAV_STORM32_GIMBAL_ACTION = 1
	// MAV_STORM32_GIMBAL_ACTION_CALIBRATION enum. Trigger the gimbal device to run a calibration
	MAV_STORM32_GIMBAL_ACTION_CALIBRATION MAV_STORM32_GIMBAL_ACTION = 2
	// MAV_STORM32_GIMBAL_ACTION_DISCOVER_MANAGER enum. Trigger gimbal device to (re)discover the gimbal manager during run time
	MAV_STORM32_GIMBAL_ACTION_DISCOVER_MANAGER MAV_STORM32_GIMBAL_ACTION = 3
)

func (MAV_STORM32_GIMBAL_ACTION) Bitmask added in v1.3.0

func (e MAV_STORM32_GIMBAL_ACTION) Bitmask() string

Bitmask return string representetion of intersects MAV_STORM32_GIMBAL_ACTION enums

func (MAV_STORM32_GIMBAL_ACTION) MarshalBinary added in v1.3.0

func (e MAV_STORM32_GIMBAL_ACTION) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_STORM32_GIMBAL_ACTION) String added in v1.3.0

func (e MAV_STORM32_GIMBAL_ACTION) String() string

func (*MAV_STORM32_GIMBAL_ACTION) UnmarshalBinary added in v1.3.0

func (e *MAV_STORM32_GIMBAL_ACTION) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS added in v1.3.0

type MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS int

MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS type. Gimbal device capability flags.

const (
	// MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT enum. Gimbal device supports a retracted position
	MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS = 1
	// MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL enum. Gimbal device supports a horizontal, forward looking position, stabilized. Can also be used to reset the gimbal's orientation
	MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS = 2
	// MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS enum. Gimbal device supports rotating around roll axis
	MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS = 4
	// MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW enum. Gimbal device supports to follow a roll angle relative to the vehicle
	MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS = 8
	// MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK enum. Gimbal device supports locking to an roll angle (generally that's the default)
	MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS = 16
	// MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS enum. Gimbal device supports rotating around pitch axis
	MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS = 32
	// MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW enum. Gimbal device supports to follow a pitch angle relative to the vehicle
	MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS = 64
	// MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK enum. Gimbal device supports locking to an pitch angle (generally that's the default)
	MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS = 128
	// MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS enum. Gimbal device supports rotating around yaw axis
	MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS = 256
	// MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW enum. Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default)
	MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS = 512
	// MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK enum. Gimbal device supports locking to a heading angle
	MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS = 1024
	// MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_INFINITE_YAW enum. Gimbal device supports yawing/panning infinitely (e.g. using a slip ring)
	MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_INFINITE_YAW MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS = 2048
	// MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ABSOLUTE_YAW enum. Gimbal device supports absolute yaw angles (this usually requires support by an autopilot, and can be dynamic, i.e., go on and off during runtime)
	MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ABSOLUTE_YAW MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS = 65536
	// MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RC enum. Gimbal device supports control via an RC input signal
	MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RC MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS = 131072
)

func (MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS) Bitmask added in v1.3.0

Bitmask return string representetion of intersects MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS enums

func (MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS) MarshalBinary added in v1.3.0

func (e MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS) String added in v1.3.0

func (*MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS) UnmarshalBinary added in v1.3.0

func (e *MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS added in v1.3.0

type MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS int

MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS type. Gimbal device error and condition flags (0 means no error or other condition).

const (
	// MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT enum. Gimbal device is limited by hardware roll limit
	MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS = 1
	// MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT enum. Gimbal device is limited by hardware pitch limit
	MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS = 2
	// MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT enum. Gimbal device is limited by hardware yaw limit
	MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS = 4
	// MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR enum. There is an error with the gimbal device's encoders
	MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS = 8
	// MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR enum. There is an error with the gimbal device's power source
	MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS = 16
	// MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR enum. There is an error with the gimbal device's motors
	MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS = 32
	// MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR enum. There is an error with the gimbal device's software
	MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS = 64
	// MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR enum. There is an error with the gimbal device's communication
	MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS = 128
	// MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING enum. Gimbal device is currently calibrating (not an error)
	MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS = 256
	// MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER enum. Gimbal device is not assigned to a gimbal manager (not an error)
	MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS = 32768
)

func (MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS) Bitmask added in v1.3.0

Bitmask return string representetion of intersects MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS enums

func (MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS) MarshalBinary added in v1.3.0

func (e MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS) String added in v1.3.0

func (*MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS) UnmarshalBinary added in v1.3.0

func (e *MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_STORM32_GIMBAL_DEVICE_FLAGS added in v1.3.0

type MAV_STORM32_GIMBAL_DEVICE_FLAGS int

MAV_STORM32_GIMBAL_DEVICE_FLAGS type. Flags for gimbal device operation. Used for setting and reporting, unless specified otherwise. Settings which are in violation of the capability flags are ignored by the gimbal device.

const (
	// MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT enum. Retracted safe position (no stabilization), takes presedence over NEUTRAL flag. If supported by the gimbal, the angles in the retracted position can be set in addition
	MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT MAV_STORM32_GIMBAL_DEVICE_FLAGS = 1
	// MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL enum. Neutral position (horizontal, forward looking, with stabiliziation)
	MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL MAV_STORM32_GIMBAL_DEVICE_FLAGS = 2
	// MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK enum. Lock roll angle to absolute angle relative to horizon (not relative to drone). This is generally the default
	MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK MAV_STORM32_GIMBAL_DEVICE_FLAGS = 4
	// MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK enum. Lock pitch angle to absolute angle relative to horizon (not relative to drone). This is generally the default
	MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK MAV_STORM32_GIMBAL_DEVICE_FLAGS = 8
	// MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK enum. Lock yaw angle to absolute angle relative to earth (not relative to drone). When the YAW_ABSOLUTE flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute), else it is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle)
	MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK MAV_STORM32_GIMBAL_DEVICE_FLAGS = 16
	// MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE enum. Gimbal device can accept absolute yaw angle input. This flag cannot be set, is only for reporting (attempts to set it are rejected by the gimbal device)
	MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE MAV_STORM32_GIMBAL_DEVICE_FLAGS = 256
	// MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE enum. Yaw angle is absolute (is only accepted if CAN_ACCEPT_YAW_ABSOLUTE is set). If this flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute), else it is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle)
	MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE MAV_STORM32_GIMBAL_DEVICE_FLAGS = 512
	// MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE enum. RC control. The RC input signal fed to the gimbal device exclusively controls the gimbal's orientation. Overrides RC_MIXED flag if that is also set
	MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE MAV_STORM32_GIMBAL_DEVICE_FLAGS = 1024
	// MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED enum. RC control. The RC input signal fed to the gimbal device is mixed into the gimbal's orientation. Is overriden by RC_EXCLUSIVE flag if that is also set
	MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED MAV_STORM32_GIMBAL_DEVICE_FLAGS = 2048
	// MAV_STORM32_GIMBAL_DEVICE_FLAGS_NONE enum. UINT16_MAX = ignore
	MAV_STORM32_GIMBAL_DEVICE_FLAGS_NONE MAV_STORM32_GIMBAL_DEVICE_FLAGS = 65535
)

func (MAV_STORM32_GIMBAL_DEVICE_FLAGS) Bitmask added in v1.3.0

Bitmask return string representetion of intersects MAV_STORM32_GIMBAL_DEVICE_FLAGS enums

func (MAV_STORM32_GIMBAL_DEVICE_FLAGS) MarshalBinary added in v1.3.0

func (e MAV_STORM32_GIMBAL_DEVICE_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_STORM32_GIMBAL_DEVICE_FLAGS) String added in v1.3.0

func (*MAV_STORM32_GIMBAL_DEVICE_FLAGS) UnmarshalBinary added in v1.3.0

func (e *MAV_STORM32_GIMBAL_DEVICE_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS added in v1.3.0

type MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS int

MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS type. Gimbal manager capability flags.

const (
	// MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_HAS_PROFILES enum. The gimbal manager supports several profiles
	MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_HAS_PROFILES MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS = 1
	// MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_CHANGE enum. The gimbal manager supports changing the gimbal manager during run time, i.e. can be enabled/disabled
	MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_CHANGE MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS = 2
)

func (MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS) Bitmask added in v1.3.0

Bitmask return string representetion of intersects MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS enums

func (MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS) MarshalBinary added in v1.3.0

func (e MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS) String added in v1.3.0

func (*MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS) UnmarshalBinary added in v1.3.0

func (e *MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_STORM32_GIMBAL_MANAGER_CLIENT added in v1.3.0

type MAV_STORM32_GIMBAL_MANAGER_CLIENT int

MAV_STORM32_GIMBAL_MANAGER_CLIENT type. Gimbal manager client ID. In a prioritizing profile, the priorities are determined by the implementation; they could e.g. be custom1 > onboard > GCS > autopilot/camera > GCS2 > custom2.

const (
	// MAV_STORM32_GIMBAL_MANAGER_CLIENT_NONE enum. For convenience
	MAV_STORM32_GIMBAL_MANAGER_CLIENT_NONE MAV_STORM32_GIMBAL_MANAGER_CLIENT = 0
	// MAV_STORM32_GIMBAL_MANAGER_CLIENT_ONBOARD enum. This is the onboard/companion computer client
	MAV_STORM32_GIMBAL_MANAGER_CLIENT_ONBOARD MAV_STORM32_GIMBAL_MANAGER_CLIENT = 1
	// MAV_STORM32_GIMBAL_MANAGER_CLIENT_AUTOPILOT enum. This is the autopilot client
	MAV_STORM32_GIMBAL_MANAGER_CLIENT_AUTOPILOT MAV_STORM32_GIMBAL_MANAGER_CLIENT = 2
	// MAV_STORM32_GIMBAL_MANAGER_CLIENT_GCS enum. This is the GCS client
	MAV_STORM32_GIMBAL_MANAGER_CLIENT_GCS MAV_STORM32_GIMBAL_MANAGER_CLIENT = 3
	// MAV_STORM32_GIMBAL_MANAGER_CLIENT_CAMERA enum. This is the camera client
	MAV_STORM32_GIMBAL_MANAGER_CLIENT_CAMERA MAV_STORM32_GIMBAL_MANAGER_CLIENT = 4
	// MAV_STORM32_GIMBAL_MANAGER_CLIENT_GCS2 enum. This is the GCS2 client
	MAV_STORM32_GIMBAL_MANAGER_CLIENT_GCS2 MAV_STORM32_GIMBAL_MANAGER_CLIENT = 5
	// MAV_STORM32_GIMBAL_MANAGER_CLIENT_CAMERA2 enum. This is the camera2 client
	MAV_STORM32_GIMBAL_MANAGER_CLIENT_CAMERA2 MAV_STORM32_GIMBAL_MANAGER_CLIENT = 6
	// MAV_STORM32_GIMBAL_MANAGER_CLIENT_CUSTOM enum. This is the custom client
	MAV_STORM32_GIMBAL_MANAGER_CLIENT_CUSTOM MAV_STORM32_GIMBAL_MANAGER_CLIENT = 7
	// MAV_STORM32_GIMBAL_MANAGER_CLIENT_CUSTOM2 enum. This is the custom2 client
	MAV_STORM32_GIMBAL_MANAGER_CLIENT_CUSTOM2 MAV_STORM32_GIMBAL_MANAGER_CLIENT = 8
)

func (MAV_STORM32_GIMBAL_MANAGER_CLIENT) Bitmask added in v1.3.0

Bitmask return string representetion of intersects MAV_STORM32_GIMBAL_MANAGER_CLIENT enums

func (MAV_STORM32_GIMBAL_MANAGER_CLIENT) MarshalBinary added in v1.3.0

func (e MAV_STORM32_GIMBAL_MANAGER_CLIENT) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_STORM32_GIMBAL_MANAGER_CLIENT) String added in v1.3.0

func (*MAV_STORM32_GIMBAL_MANAGER_CLIENT) UnmarshalBinary added in v1.3.0

func (e *MAV_STORM32_GIMBAL_MANAGER_CLIENT) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_STORM32_GIMBAL_MANAGER_FLAGS added in v1.3.0

type MAV_STORM32_GIMBAL_MANAGER_FLAGS int

MAV_STORM32_GIMBAL_MANAGER_FLAGS type. Flags for gimbal manager operation. Used for setting and reporting, unless specified otherwise. If a setting is accepted by the gimbal manger, is reported in the STORM32_GIMBAL_MANAGER_STATUS message.

const (
	// MAV_STORM32_GIMBAL_MANAGER_FLAGS_NONE enum. 0 = ignore
	MAV_STORM32_GIMBAL_MANAGER_FLAGS_NONE MAV_STORM32_GIMBAL_MANAGER_FLAGS = 0
	// MAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE enum. Request to set RC input to active, or report RC input is active. Implies RC mixed. RC exclusive is achieved by setting all clients to inactive
	MAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE MAV_STORM32_GIMBAL_MANAGER_FLAGS = 1
	// MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE enum. Request to set onboard/companion computer client to active, or report this client is active
	MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE MAV_STORM32_GIMBAL_MANAGER_FLAGS = 2
	// MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE enum. Request to set autopliot client to active, or report this client is active
	MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE MAV_STORM32_GIMBAL_MANAGER_FLAGS = 4
	// MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE enum. Request to set GCS client to active, or report this client is active
	MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE MAV_STORM32_GIMBAL_MANAGER_FLAGS = 8
	// MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE enum. Request to set camera client to active, or report this client is active
	MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE MAV_STORM32_GIMBAL_MANAGER_FLAGS = 16
	// MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE enum. Request to set GCS2 client to active, or report this client is active
	MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE MAV_STORM32_GIMBAL_MANAGER_FLAGS = 32
	// MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE enum. Request to set camera2 client to active, or report this client is active
	MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE MAV_STORM32_GIMBAL_MANAGER_FLAGS = 64
	// MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE enum. Request to set custom client to active, or report this client is active
	MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE MAV_STORM32_GIMBAL_MANAGER_FLAGS = 128
	// MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE enum. Request to set custom2 client to active, or report this client is active
	MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE MAV_STORM32_GIMBAL_MANAGER_FLAGS = 256
	// MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON enum. Request supervision. This flag is only for setting, it is not reported
	MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON MAV_STORM32_GIMBAL_MANAGER_FLAGS = 512
	// MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE enum. Release supervision. This flag is only for setting, it is not reported
	MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE MAV_STORM32_GIMBAL_MANAGER_FLAGS = 1024
)

func (MAV_STORM32_GIMBAL_MANAGER_FLAGS) Bitmask added in v1.3.0

Bitmask return string representetion of intersects MAV_STORM32_GIMBAL_MANAGER_FLAGS enums

func (MAV_STORM32_GIMBAL_MANAGER_FLAGS) MarshalBinary added in v1.3.0

func (e MAV_STORM32_GIMBAL_MANAGER_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_STORM32_GIMBAL_MANAGER_FLAGS) String added in v1.3.0

func (*MAV_STORM32_GIMBAL_MANAGER_FLAGS) UnmarshalBinary added in v1.3.0

func (e *MAV_STORM32_GIMBAL_MANAGER_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_STORM32_GIMBAL_MANAGER_PROFILE added in v1.3.0

type MAV_STORM32_GIMBAL_MANAGER_PROFILE int

MAV_STORM32_GIMBAL_MANAGER_PROFILE type. Gimbal manager profiles. Only standard profiles are defined. Any implementation can define it's own profile in addition, and should use enum values > 16.

const (
	// MAV_STORM32_GIMBAL_MANAGER_PROFILE_DEFAULT enum. Default profile. Implementation specific
	MAV_STORM32_GIMBAL_MANAGER_PROFILE_DEFAULT MAV_STORM32_GIMBAL_MANAGER_PROFILE = 0
	// MAV_STORM32_GIMBAL_MANAGER_PROFILE_CUSTOM enum. Custom profile. Configurable profile according to the STorM32 definition. Is configured with STORM32_GIMBAL_MANAGER_PROFIL
	MAV_STORM32_GIMBAL_MANAGER_PROFILE_CUSTOM MAV_STORM32_GIMBAL_MANAGER_PROFILE = 1
	// MAV_STORM32_GIMBAL_MANAGER_PROFILE_COOPERATIVE enum. Default cooperative profile. Uses STorM32 custom profile with default settings to achieve cooperative behavior
	MAV_STORM32_GIMBAL_MANAGER_PROFILE_COOPERATIVE MAV_STORM32_GIMBAL_MANAGER_PROFILE = 2
	// MAV_STORM32_GIMBAL_MANAGER_PROFILE_EXCLUSIVE enum. Default exclusive profile. Uses STorM32 custom profile with default settings to achieve exclusive behavior
	MAV_STORM32_GIMBAL_MANAGER_PROFILE_EXCLUSIVE MAV_STORM32_GIMBAL_MANAGER_PROFILE = 3
	// MAV_STORM32_GIMBAL_MANAGER_PROFILE_PRIORITY_COOPERATIVE enum. Default priority profile with cooperative behavior for equal priority. Uses STorM32 custom profile with default settings to achieve priority-based behavior
	MAV_STORM32_GIMBAL_MANAGER_PROFILE_PRIORITY_COOPERATIVE MAV_STORM32_GIMBAL_MANAGER_PROFILE = 4
	// MAV_STORM32_GIMBAL_MANAGER_PROFILE_PRIORITY_EXCLUSIVE enum. Default priority profile with exclusive behavior for equal priority. Uses STorM32 custom profile with default settings to achieve priority-based behavior
	MAV_STORM32_GIMBAL_MANAGER_PROFILE_PRIORITY_EXCLUSIVE MAV_STORM32_GIMBAL_MANAGER_PROFILE = 5
)

func (MAV_STORM32_GIMBAL_MANAGER_PROFILE) Bitmask added in v1.3.0

Bitmask return string representetion of intersects MAV_STORM32_GIMBAL_MANAGER_PROFILE enums

func (MAV_STORM32_GIMBAL_MANAGER_PROFILE) MarshalBinary added in v1.3.0

func (e MAV_STORM32_GIMBAL_MANAGER_PROFILE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_STORM32_GIMBAL_MANAGER_PROFILE) String added in v1.3.0

func (*MAV_STORM32_GIMBAL_MANAGER_PROFILE) UnmarshalBinary added in v1.3.0

func (e *MAV_STORM32_GIMBAL_MANAGER_PROFILE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS added in v1.3.0

type MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS int

MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS type. Flags for gimbal manager set up. Used for setting and reporting, unless specified otherwise.

const (
	// MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_ENABLE enum. Enable gimbal manager. This flag is only for setting, is not reported
	MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_ENABLE MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS = 16384
	// MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_DISABLE enum. Disable gimbal manager. This flag is only for setting, is not reported
	MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_DISABLE MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS = 32768
)

func (MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS) Bitmask added in v1.3.0

Bitmask return string representetion of intersects MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS enums

func (MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS) MarshalBinary added in v1.3.0

func (e MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS) String added in v1.3.0

func (*MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS) UnmarshalBinary added in v1.3.0

func (e *MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_STORM32_TUNNEL_PAYLOAD_TYPE added in v1.3.0

type MAV_STORM32_TUNNEL_PAYLOAD_TYPE int

MAV_STORM32_TUNNEL_PAYLOAD_TYPE type

const (
	// MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH1_IN enum. Registered for STorM32 gimbal controller
	MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH1_IN MAV_STORM32_TUNNEL_PAYLOAD_TYPE = 200
	// MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH1_OUT enum. Registered for STorM32 gimbal controller
	MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH1_OUT MAV_STORM32_TUNNEL_PAYLOAD_TYPE = 201
	// MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH2_IN enum. Registered for STorM32 gimbal controller
	MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH2_IN MAV_STORM32_TUNNEL_PAYLOAD_TYPE = 202
	// MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH2_OUT enum. Registered for STorM32 gimbal controller
	MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH2_OUT MAV_STORM32_TUNNEL_PAYLOAD_TYPE = 203
	// MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH3_IN enum. Registered for STorM32 gimbal controller
	MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH3_IN MAV_STORM32_TUNNEL_PAYLOAD_TYPE = 204
	// MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH3_OUT enum. Registered for STorM32 gimbal controller
	MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH3_OUT MAV_STORM32_TUNNEL_PAYLOAD_TYPE = 205
	// MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6 enum. Registered for STorM32 gimbal controller
	MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6 MAV_STORM32_TUNNEL_PAYLOAD_TYPE = 206
	// MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7 enum. Registered for STorM32 gimbal controller
	MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7 MAV_STORM32_TUNNEL_PAYLOAD_TYPE = 207
	// MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8 enum. Registered for STorM32 gimbal controller
	MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8 MAV_STORM32_TUNNEL_PAYLOAD_TYPE = 208
	// MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9 enum. Registered for STorM32 gimbal controller
	MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9 MAV_STORM32_TUNNEL_PAYLOAD_TYPE = 209
)

func (MAV_STORM32_TUNNEL_PAYLOAD_TYPE) Bitmask added in v1.3.0

Bitmask return string representetion of intersects MAV_STORM32_TUNNEL_PAYLOAD_TYPE enums

func (MAV_STORM32_TUNNEL_PAYLOAD_TYPE) MarshalBinary added in v1.3.0

func (e MAV_STORM32_TUNNEL_PAYLOAD_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_STORM32_TUNNEL_PAYLOAD_TYPE) String added in v1.3.0

func (*MAV_STORM32_TUNNEL_PAYLOAD_TYPE) UnmarshalBinary added in v1.3.0

func (e *MAV_STORM32_TUNNEL_PAYLOAD_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_SYS_STATUS_SENSOR

type MAV_SYS_STATUS_SENSOR int

MAV_SYS_STATUS_SENSOR type. These encode the sensors whose status is sent as part of the SYS_STATUS message.

const (
	// MAV_SYS_STATUS_SENSOR_3D_GYRO enum. 0x01 3D gyro
	MAV_SYS_STATUS_SENSOR_3D_GYRO MAV_SYS_STATUS_SENSOR = 1
	// MAV_SYS_STATUS_SENSOR_3D_ACCEL enum. 0x02 3D accelerometer
	MAV_SYS_STATUS_SENSOR_3D_ACCEL MAV_SYS_STATUS_SENSOR = 2
	// MAV_SYS_STATUS_SENSOR_3D_MAG enum. 0x04 3D magnetometer
	MAV_SYS_STATUS_SENSOR_3D_MAG MAV_SYS_STATUS_SENSOR = 4
	// MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE enum. 0x08 absolute pressure
	MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE MAV_SYS_STATUS_SENSOR = 8
	// MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE enum. 0x10 differential pressure
	MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE MAV_SYS_STATUS_SENSOR = 16
	// MAV_SYS_STATUS_SENSOR_GPS enum. 0x20 GPS
	MAV_SYS_STATUS_SENSOR_GPS MAV_SYS_STATUS_SENSOR = 32
	// MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW enum. 0x40 optical flow
	MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW MAV_SYS_STATUS_SENSOR = 64
	// MAV_SYS_STATUS_SENSOR_VISION_POSITION enum. 0x80 computer vision position
	MAV_SYS_STATUS_SENSOR_VISION_POSITION MAV_SYS_STATUS_SENSOR = 128
	// MAV_SYS_STATUS_SENSOR_LASER_POSITION enum. 0x100 laser based position
	MAV_SYS_STATUS_SENSOR_LASER_POSITION MAV_SYS_STATUS_SENSOR = 256
	// MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH enum. 0x200 external ground truth (Vicon or Leica)
	MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH MAV_SYS_STATUS_SENSOR = 512
	// MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL enum. 0x400 3D angular rate control
	MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL MAV_SYS_STATUS_SENSOR = 1024
	// MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION enum. 0x800 attitude stabilization
	MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION MAV_SYS_STATUS_SENSOR = 2048
	// MAV_SYS_STATUS_SENSOR_YAW_POSITION enum. 0x1000 yaw position
	MAV_SYS_STATUS_SENSOR_YAW_POSITION MAV_SYS_STATUS_SENSOR = 4096
	// MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL enum. 0x2000 z/altitude control
	MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL MAV_SYS_STATUS_SENSOR = 8192
	// MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL enum. 0x4000 x/y position control
	MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL MAV_SYS_STATUS_SENSOR = 16384
	// MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS enum. 0x8000 motor outputs / control
	MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS MAV_SYS_STATUS_SENSOR = 32768
	// MAV_SYS_STATUS_SENSOR_RC_RECEIVER enum. 0x10000 rc receiver
	MAV_SYS_STATUS_SENSOR_RC_RECEIVER MAV_SYS_STATUS_SENSOR = 65536
	// MAV_SYS_STATUS_SENSOR_3D_GYRO2 enum. 0x20000 2nd 3D gyro
	MAV_SYS_STATUS_SENSOR_3D_GYRO2 MAV_SYS_STATUS_SENSOR = 131072
	// MAV_SYS_STATUS_SENSOR_3D_ACCEL2 enum. 0x40000 2nd 3D accelerometer
	MAV_SYS_STATUS_SENSOR_3D_ACCEL2 MAV_SYS_STATUS_SENSOR = 262144
	// MAV_SYS_STATUS_SENSOR_3D_MAG2 enum. 0x80000 2nd 3D magnetometer
	MAV_SYS_STATUS_SENSOR_3D_MAG2 MAV_SYS_STATUS_SENSOR = 524288
	// MAV_SYS_STATUS_GEOFENCE enum. 0x100000 geofence
	MAV_SYS_STATUS_GEOFENCE MAV_SYS_STATUS_SENSOR = 1048576
	// MAV_SYS_STATUS_AHRS enum. 0x200000 AHRS subsystem health
	MAV_SYS_STATUS_AHRS MAV_SYS_STATUS_SENSOR = 2097152
	// MAV_SYS_STATUS_TERRAIN enum. 0x400000 Terrain subsystem health
	MAV_SYS_STATUS_TERRAIN MAV_SYS_STATUS_SENSOR = 4194304
	// MAV_SYS_STATUS_REVERSE_MOTOR enum. 0x800000 Motors are reversed
	MAV_SYS_STATUS_REVERSE_MOTOR MAV_SYS_STATUS_SENSOR = 8388608
	// MAV_SYS_STATUS_LOGGING enum. 0x1000000 Logging
	MAV_SYS_STATUS_LOGGING MAV_SYS_STATUS_SENSOR = 16777216
	// MAV_SYS_STATUS_SENSOR_BATTERY enum. 0x2000000 Battery
	MAV_SYS_STATUS_SENSOR_BATTERY MAV_SYS_STATUS_SENSOR = 33554432
	// MAV_SYS_STATUS_SENSOR_PROXIMITY enum. 0x4000000 Proximity
	MAV_SYS_STATUS_SENSOR_PROXIMITY MAV_SYS_STATUS_SENSOR = 67108864
	// MAV_SYS_STATUS_SENSOR_SATCOM enum. 0x8000000 Satellite Communication
	MAV_SYS_STATUS_SENSOR_SATCOM MAV_SYS_STATUS_SENSOR = 134217728
	// MAV_SYS_STATUS_PREARM_CHECK enum. 0x10000000 pre-arm check status. Always healthy when armed
	MAV_SYS_STATUS_PREARM_CHECK MAV_SYS_STATUS_SENSOR = 268435456
	// MAV_SYS_STATUS_OBSTACLE_AVOIDANCE enum. 0x20000000 Avoidance/collision prevention
	MAV_SYS_STATUS_OBSTACLE_AVOIDANCE MAV_SYS_STATUS_SENSOR = 536870912
	// MAV_SYS_STATUS_SENSOR_PROPULSION enum. 0x40000000 propulsion (actuator, esc, motor or propellor)
	MAV_SYS_STATUS_SENSOR_PROPULSION MAV_SYS_STATUS_SENSOR = 1073741824
)

func (MAV_SYS_STATUS_SENSOR) Bitmask

func (e MAV_SYS_STATUS_SENSOR) Bitmask() string

Bitmask return string representetion of intersects MAV_SYS_STATUS_SENSOR enums

func (MAV_SYS_STATUS_SENSOR) MarshalBinary

func (e MAV_SYS_STATUS_SENSOR) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_SYS_STATUS_SENSOR) String

func (e MAV_SYS_STATUS_SENSOR) String() string

func (*MAV_SYS_STATUS_SENSOR) UnmarshalBinary

func (e *MAV_SYS_STATUS_SENSOR) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_TUNNEL_PAYLOAD_TYPE

type MAV_TUNNEL_PAYLOAD_TYPE int

MAV_TUNNEL_PAYLOAD_TYPE type

const (
	// MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN enum. Encoding of payload unknown
	MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN MAV_TUNNEL_PAYLOAD_TYPE = 0
	// MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED0 enum. Registered for STorM32 gimbal controller
	MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED0 MAV_TUNNEL_PAYLOAD_TYPE = 200
	// MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED1 enum. Registered for STorM32 gimbal controller
	MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED1 MAV_TUNNEL_PAYLOAD_TYPE = 201
	// MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED2 enum. Registered for STorM32 gimbal controller
	MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED2 MAV_TUNNEL_PAYLOAD_TYPE = 202
	// MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED3 enum. Registered for STorM32 gimbal controller
	MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED3 MAV_TUNNEL_PAYLOAD_TYPE = 203
	// MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED4 enum. Registered for STorM32 gimbal controller
	MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED4 MAV_TUNNEL_PAYLOAD_TYPE = 204
	// MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED5 enum. Registered for STorM32 gimbal controller
	MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED5 MAV_TUNNEL_PAYLOAD_TYPE = 205
	// MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6 enum. Registered for STorM32 gimbal controller
	MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6 MAV_TUNNEL_PAYLOAD_TYPE = 206
	// MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7 enum. Registered for STorM32 gimbal controller
	MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7 MAV_TUNNEL_PAYLOAD_TYPE = 207
	// MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8 enum. Registered for STorM32 gimbal controller
	MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8 MAV_TUNNEL_PAYLOAD_TYPE = 208
	// MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9 enum. Registered for STorM32 gimbal controller
	MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9 MAV_TUNNEL_PAYLOAD_TYPE = 209
)

func (MAV_TUNNEL_PAYLOAD_TYPE) Bitmask

func (e MAV_TUNNEL_PAYLOAD_TYPE) Bitmask() string

Bitmask return string representetion of intersects MAV_TUNNEL_PAYLOAD_TYPE enums

func (MAV_TUNNEL_PAYLOAD_TYPE) MarshalBinary

func (e MAV_TUNNEL_PAYLOAD_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_TUNNEL_PAYLOAD_TYPE) String

func (e MAV_TUNNEL_PAYLOAD_TYPE) String() string

func (*MAV_TUNNEL_PAYLOAD_TYPE) UnmarshalBinary

func (e *MAV_TUNNEL_PAYLOAD_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_TYPE

type MAV_TYPE int

MAV_TYPE type. MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA).

const (
	// MAV_TYPE_GENERIC enum. Generic micro air vehicle
	MAV_TYPE_GENERIC MAV_TYPE = 0
	// MAV_TYPE_FIXED_WING enum. Fixed wing aircraft
	MAV_TYPE_FIXED_WING MAV_TYPE = 1
	// MAV_TYPE_QUADROTOR enum. Quadrotor
	MAV_TYPE_QUADROTOR MAV_TYPE = 2
	// MAV_TYPE_COAXIAL enum. Coaxial helicopter
	MAV_TYPE_COAXIAL MAV_TYPE = 3
	// MAV_TYPE_HELICOPTER enum. Normal helicopter with tail rotor
	MAV_TYPE_HELICOPTER MAV_TYPE = 4
	// MAV_TYPE_ANTENNA_TRACKER enum. Ground installation
	MAV_TYPE_ANTENNA_TRACKER MAV_TYPE = 5
	// MAV_TYPE_GCS enum. Operator control unit / ground control station
	MAV_TYPE_GCS MAV_TYPE = 6
	// MAV_TYPE_AIRSHIP enum. Airship, controlled
	MAV_TYPE_AIRSHIP MAV_TYPE = 7
	// MAV_TYPE_FREE_BALLOON enum. Free balloon, uncontrolled
	MAV_TYPE_FREE_BALLOON MAV_TYPE = 8
	// MAV_TYPE_ROCKET enum. Rocket
	MAV_TYPE_ROCKET MAV_TYPE = 9
	// MAV_TYPE_GROUND_ROVER enum. Ground rover
	MAV_TYPE_GROUND_ROVER MAV_TYPE = 10
	// MAV_TYPE_SURFACE_BOAT enum. Surface vessel, boat, ship
	MAV_TYPE_SURFACE_BOAT MAV_TYPE = 11
	// MAV_TYPE_SUBMARINE enum. Submarine
	MAV_TYPE_SUBMARINE MAV_TYPE = 12
	// MAV_TYPE_HEXAROTOR enum. Hexarotor
	MAV_TYPE_HEXAROTOR MAV_TYPE = 13
	// MAV_TYPE_OCTOROTOR enum. Octorotor
	MAV_TYPE_OCTOROTOR MAV_TYPE = 14
	// MAV_TYPE_TRICOPTER enum. Tricopter
	MAV_TYPE_TRICOPTER MAV_TYPE = 15
	// MAV_TYPE_FLAPPING_WING enum. Flapping wing
	MAV_TYPE_FLAPPING_WING MAV_TYPE = 16
	// MAV_TYPE_KITE enum. Kite
	MAV_TYPE_KITE MAV_TYPE = 17
	// MAV_TYPE_ONBOARD_CONTROLLER enum. Onboard companion controller
	MAV_TYPE_ONBOARD_CONTROLLER MAV_TYPE = 18
	// MAV_TYPE_VTOL_DUOROTOR enum. Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter
	MAV_TYPE_VTOL_DUOROTOR MAV_TYPE = 19
	// MAV_TYPE_VTOL_QUADROTOR enum. Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter
	MAV_TYPE_VTOL_QUADROTOR MAV_TYPE = 20
	// MAV_TYPE_VTOL_TILTROTOR enum. Tiltrotor VTOL
	MAV_TYPE_VTOL_TILTROTOR MAV_TYPE = 21
	// MAV_TYPE_VTOL_RESERVED2 enum. VTOL reserved 2
	MAV_TYPE_VTOL_RESERVED2 MAV_TYPE = 22
	// MAV_TYPE_VTOL_RESERVED3 enum. VTOL reserved 3
	MAV_TYPE_VTOL_RESERVED3 MAV_TYPE = 23
	// MAV_TYPE_VTOL_RESERVED4 enum. VTOL reserved 4
	MAV_TYPE_VTOL_RESERVED4 MAV_TYPE = 24
	// MAV_TYPE_VTOL_RESERVED5 enum. VTOL reserved 5
	MAV_TYPE_VTOL_RESERVED5 MAV_TYPE = 25
	// MAV_TYPE_GIMBAL enum. Gimbal
	MAV_TYPE_GIMBAL MAV_TYPE = 26
	// MAV_TYPE_ADSB enum. ADSB system
	MAV_TYPE_ADSB MAV_TYPE = 27
	// MAV_TYPE_PARAFOIL enum. Steerable, nonrigid airfoil
	MAV_TYPE_PARAFOIL MAV_TYPE = 28
	// MAV_TYPE_DODECAROTOR enum. Dodecarotor
	MAV_TYPE_DODECAROTOR MAV_TYPE = 29
	// MAV_TYPE_CAMERA enum. Camera
	MAV_TYPE_CAMERA MAV_TYPE = 30
	// MAV_TYPE_CHARGING_STATION enum. Charging station
	MAV_TYPE_CHARGING_STATION MAV_TYPE = 31
	// MAV_TYPE_FLARM enum. FLARM collision avoidance system
	MAV_TYPE_FLARM MAV_TYPE = 32
	// MAV_TYPE_SERVO enum. Servo
	MAV_TYPE_SERVO MAV_TYPE = 33
	// MAV_TYPE_ODID enum. Open Drone ID. See https://mavlink.io/en/services/opendroneid.html
	MAV_TYPE_ODID MAV_TYPE = 34
	// MAV_TYPE_DECAROTOR enum. Decarotor
	MAV_TYPE_DECAROTOR MAV_TYPE = 35
)

func (MAV_TYPE) Bitmask

func (e MAV_TYPE) Bitmask() string

Bitmask return string representetion of intersects MAV_TYPE enums

func (MAV_TYPE) MarshalBinary

func (e MAV_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_TYPE) String

func (e MAV_TYPE) String() string

func (*MAV_TYPE) UnmarshalBinary

func (e *MAV_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_VTOL_STATE

type MAV_VTOL_STATE int

MAV_VTOL_STATE type. Enumeration of VTOL states

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

func (MAV_VTOL_STATE) Bitmask

func (e MAV_VTOL_STATE) Bitmask() string

Bitmask return string representetion of intersects MAV_VTOL_STATE enums

func (MAV_VTOL_STATE) MarshalBinary

func (e MAV_VTOL_STATE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_VTOL_STATE) String

func (e MAV_VTOL_STATE) String() string

func (*MAV_VTOL_STATE) UnmarshalBinary

func (e *MAV_VTOL_STATE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MAV_WINCH_STATUS_FLAG

type MAV_WINCH_STATUS_FLAG int

MAV_WINCH_STATUS_FLAG type. Winch status flags used in WINCH_STATUS

const (
	// MAV_WINCH_STATUS_HEALTHY enum. Winch is healthy
	MAV_WINCH_STATUS_HEALTHY MAV_WINCH_STATUS_FLAG = 1
	// MAV_WINCH_STATUS_FULLY_RETRACTED enum. Winch thread is fully retracted
	MAV_WINCH_STATUS_FULLY_RETRACTED MAV_WINCH_STATUS_FLAG = 2
	// MAV_WINCH_STATUS_MOVING enum. Winch motor is moving
	MAV_WINCH_STATUS_MOVING MAV_WINCH_STATUS_FLAG = 4
	// MAV_WINCH_STATUS_CLUTCH_ENGAGED enum. Winch clutch is engaged allowing motor to move freely
	MAV_WINCH_STATUS_CLUTCH_ENGAGED MAV_WINCH_STATUS_FLAG = 8
)

func (MAV_WINCH_STATUS_FLAG) Bitmask

func (e MAV_WINCH_STATUS_FLAG) Bitmask() string

Bitmask return string representetion of intersects MAV_WINCH_STATUS_FLAG enums

func (MAV_WINCH_STATUS_FLAG) MarshalBinary

func (e MAV_WINCH_STATUS_FLAG) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MAV_WINCH_STATUS_FLAG) String

func (e MAV_WINCH_STATUS_FLAG) String() string

func (*MAV_WINCH_STATUS_FLAG) UnmarshalBinary

func (e *MAV_WINCH_STATUS_FLAG) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MOTOR_TEST_ORDER

type MOTOR_TEST_ORDER int

MOTOR_TEST_ORDER type

const (
	// MOTOR_TEST_ORDER_DEFAULT enum. default autopilot motor test method
	MOTOR_TEST_ORDER_DEFAULT MOTOR_TEST_ORDER = 0
	// MOTOR_TEST_ORDER_SEQUENCE enum. motor numbers are specified as their index in a predefined vehicle-specific sequence
	MOTOR_TEST_ORDER_SEQUENCE MOTOR_TEST_ORDER = 1
	// MOTOR_TEST_ORDER_BOARD enum. motor numbers are specified as the output as labeled on the board
	MOTOR_TEST_ORDER_BOARD MOTOR_TEST_ORDER = 2
)

func (MOTOR_TEST_ORDER) Bitmask

func (e MOTOR_TEST_ORDER) Bitmask() string

Bitmask return string representetion of intersects MOTOR_TEST_ORDER enums

func (MOTOR_TEST_ORDER) MarshalBinary

func (e MOTOR_TEST_ORDER) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MOTOR_TEST_ORDER) String

func (e MOTOR_TEST_ORDER) String() string

func (*MOTOR_TEST_ORDER) UnmarshalBinary

func (e *MOTOR_TEST_ORDER) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MOTOR_TEST_THROTTLE_TYPE

type MOTOR_TEST_THROTTLE_TYPE int

MOTOR_TEST_THROTTLE_TYPE type

const (
	// MOTOR_TEST_THROTTLE_PERCENT enum. throttle as a percentage from 0 ~ 100
	MOTOR_TEST_THROTTLE_PERCENT MOTOR_TEST_THROTTLE_TYPE = 0
	// MOTOR_TEST_THROTTLE_PWM enum. throttle as an absolute PWM value (normally in range of 1000~2000)
	MOTOR_TEST_THROTTLE_PWM MOTOR_TEST_THROTTLE_TYPE = 1
	// MOTOR_TEST_THROTTLE_PILOT enum. throttle pass-through from pilot's transmitter
	MOTOR_TEST_THROTTLE_PILOT MOTOR_TEST_THROTTLE_TYPE = 2
	// MOTOR_TEST_COMPASS_CAL enum. per-motor compass calibration test
	MOTOR_TEST_COMPASS_CAL MOTOR_TEST_THROTTLE_TYPE = 3
)

func (MOTOR_TEST_THROTTLE_TYPE) Bitmask

func (e MOTOR_TEST_THROTTLE_TYPE) Bitmask() string

Bitmask return string representetion of intersects MOTOR_TEST_THROTTLE_TYPE enums

func (MOTOR_TEST_THROTTLE_TYPE) MarshalBinary

func (e MOTOR_TEST_THROTTLE_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (MOTOR_TEST_THROTTLE_TYPE) String

func (e MOTOR_TEST_THROTTLE_TYPE) String() string

func (*MOTOR_TEST_THROTTLE_TYPE) UnmarshalBinary

func (e *MOTOR_TEST_THROTTLE_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type MagCalProgress

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

MagCalProgress struct (generated typeinfo) Reports progress of compass calibration.

func (*MagCalProgress) Dict

func (m *MagCalProgress) Dict() map[string]interface{}

ToMap (generated function)

func (*MagCalProgress) Marshal

func (m *MagCalProgress) Marshal() ([]byte, error)

Marshal (generated function)

func (MagCalProgress) MarshalEasyJSON added in v1.5.0

func (v MagCalProgress) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MagCalProgress) MarshalJSON added in v1.5.0

func (v MagCalProgress) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MagCalProgress) MsgID

func (m *MagCalProgress) MsgID() message.MessageID

MsgID (generated function)

func (*MagCalProgress) String

func (m *MagCalProgress) String() string

String (generated function)

func (*MagCalProgress) Unmarshal

func (m *MagCalProgress) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MagCalProgress) UnmarshalEasyJSON added in v1.5.0

func (v *MagCalProgress) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MagCalProgress) UnmarshalJSON added in v1.5.0

func (v *MagCalProgress) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MagCalReport

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

MagCalReport struct (generated typeinfo) Reports results of completed compass calibration. Sent until MAG_CAL_ACK received.

func (*MagCalReport) Dict

func (m *MagCalReport) Dict() map[string]interface{}

ToMap (generated function)

func (*MagCalReport) Marshal

func (m *MagCalReport) Marshal() ([]byte, error)

Marshal (generated function)

func (MagCalReport) MarshalEasyJSON added in v1.5.0

func (v MagCalReport) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MagCalReport) MarshalJSON added in v1.5.0

func (v MagCalReport) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MagCalReport) MsgID

func (m *MagCalReport) MsgID() message.MessageID

MsgID (generated function)

func (*MagCalReport) String

func (m *MagCalReport) String() string

String (generated function)

func (*MagCalReport) Unmarshal

func (m *MagCalReport) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MagCalReport) UnmarshalEasyJSON added in v1.5.0

func (v *MagCalReport) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MagCalReport) UnmarshalJSON added in v1.5.0

func (v *MagCalReport) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ManualControl

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

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

func (*ManualControl) Dict

func (m *ManualControl) Dict() map[string]interface{}

ToMap (generated function)

func (*ManualControl) Marshal

func (m *ManualControl) Marshal() ([]byte, error)

Marshal (generated function)

func (ManualControl) MarshalEasyJSON added in v1.5.0

func (v ManualControl) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ManualControl) MarshalJSON added in v1.5.0

func (v ManualControl) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ManualControl) MsgID

func (m *ManualControl) MsgID() message.MessageID

MsgID (generated function)

func (*ManualControl) String

func (m *ManualControl) String() string

String (generated function)

func (*ManualControl) Unmarshal

func (m *ManualControl) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ManualControl) UnmarshalEasyJSON added in v1.5.0

func (v *ManualControl) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ManualControl) UnmarshalJSON added in v1.5.0

func (v *ManualControl) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ManualSetpoint

type ManualSetpoint struct {
	TimeBootMs           uint32  `json:"TimeBootMs" `           // [ ms ] Timestamp (time since system boot).
	Roll                 float32 `json:"Roll" `                 // [ rad/s ] Desired roll rate
	Pitch                float32 `json:"Pitch" `                // [ rad/s ] Desired pitch rate
	Yaw                  float32 `json:"Yaw" `                  // [ rad/s ] Desired yaw rate
	Thrust               float32 `json:"Thrust" `               // Collective thrust, normalized to 0 .. 1
	ModeSwitch           uint8   `json:"ModeSwitch" `           // Flight mode switch position, 0.. 255
	ManualOverrideSwitch uint8   `json:"ManualOverrideSwitch" ` // Override mode switch position, 0.. 255
}

ManualSetpoint struct (generated typeinfo) Setpoint in roll, pitch, yaw and thrust from the operator

func (*ManualSetpoint) Dict

func (m *ManualSetpoint) Dict() map[string]interface{}

ToMap (generated function)

func (*ManualSetpoint) Marshal

func (m *ManualSetpoint) Marshal() ([]byte, error)

Marshal (generated function)

func (ManualSetpoint) MarshalEasyJSON added in v1.5.0

func (v ManualSetpoint) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ManualSetpoint) MarshalJSON added in v1.5.0

func (v ManualSetpoint) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ManualSetpoint) MsgID

func (m *ManualSetpoint) MsgID() message.MessageID

MsgID (generated function)

func (*ManualSetpoint) String

func (m *ManualSetpoint) String() string

String (generated function)

func (*ManualSetpoint) Unmarshal

func (m *ManualSetpoint) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ManualSetpoint) UnmarshalEasyJSON added in v1.5.0

func (v *ManualSetpoint) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ManualSetpoint) UnmarshalJSON added in v1.5.0

func (v *ManualSetpoint) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Meminfo

type Meminfo struct {
	Brkval  uint16 `json:"Brkval" `  // Heap top.
	Freemem uint16 `json:"Freemem" ` // [ bytes ] Free memory.
}

Meminfo struct (generated typeinfo) State of APM memory.

func (*Meminfo) Dict

func (m *Meminfo) Dict() map[string]interface{}

ToMap (generated function)

func (*Meminfo) Marshal

func (m *Meminfo) Marshal() ([]byte, error)

Marshal (generated function)

func (Meminfo) MarshalEasyJSON added in v1.5.0

func (v Meminfo) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Meminfo) MarshalJSON added in v1.5.0

func (v Meminfo) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Meminfo) MsgID

func (m *Meminfo) MsgID() message.MessageID

MsgID (generated function)

func (*Meminfo) String

func (m *Meminfo) String() string

String (generated function)

func (*Meminfo) Unmarshal

func (m *Meminfo) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Meminfo) UnmarshalEasyJSON added in v1.5.0

func (v *Meminfo) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Meminfo) UnmarshalJSON added in v1.5.0

func (v *Meminfo) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MemoryVect

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

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

func (*MemoryVect) Dict

func (m *MemoryVect) Dict() map[string]interface{}

ToMap (generated function)

func (*MemoryVect) Marshal

func (m *MemoryVect) Marshal() ([]byte, error)

Marshal (generated function)

func (MemoryVect) MarshalEasyJSON added in v1.5.0

func (v MemoryVect) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MemoryVect) MarshalJSON added in v1.5.0

func (v MemoryVect) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MemoryVect) MsgID

func (m *MemoryVect) MsgID() message.MessageID

MsgID (generated function)

func (*MemoryVect) String

func (m *MemoryVect) String() string

String (generated function)

func (*MemoryVect) Unmarshal

func (m *MemoryVect) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MemoryVect) UnmarshalEasyJSON added in v1.5.0

func (v *MemoryVect) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MemoryVect) UnmarshalJSON added in v1.5.0

func (v *MemoryVect) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MessageInterval

type MessageInterval struct {
	IntervalUs int32  `json:"IntervalUs" ` // [ us ] The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.
	MessageID  uint16 `json:"MessageID" `  // The ID of the requested MAVLink message. v1.0 is limited to 254 messages.
}

MessageInterval struct (generated typeinfo) The interval between messages for a particular MAVLink message ID. This message is the response to the MAV_CMD_GET_MESSAGE_INTERVAL command. This interface replaces DATA_STREAM.

func (*MessageInterval) Dict

func (m *MessageInterval) Dict() map[string]interface{}

ToMap (generated function)

func (*MessageInterval) Marshal

func (m *MessageInterval) Marshal() ([]byte, error)

Marshal (generated function)

func (MessageInterval) MarshalEasyJSON added in v1.5.0

func (v MessageInterval) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MessageInterval) MarshalJSON added in v1.5.0

func (v MessageInterval) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MessageInterval) MsgID

func (m *MessageInterval) MsgID() message.MessageID

MsgID (generated function)

func (*MessageInterval) String

func (m *MessageInterval) String() string

String (generated function)

func (*MessageInterval) Unmarshal

func (m *MessageInterval) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MessageInterval) UnmarshalEasyJSON added in v1.5.0

func (v *MessageInterval) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MessageInterval) UnmarshalJSON added in v1.5.0

func (v *MessageInterval) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MissionAck

type MissionAck struct {
	TargetSystem    uint8              `json:"TargetSystem" `    // System ID
	TargetComponent uint8              `json:"TargetComponent" ` // Component ID
	Type            MAV_MISSION_RESULT `json:"Type" `            // Mission result.
}

MissionAck struct (generated typeinfo) Acknowledgment message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero).

func (*MissionAck) Dict

func (m *MissionAck) Dict() map[string]interface{}

ToMap (generated function)

func (*MissionAck) Marshal

func (m *MissionAck) Marshal() ([]byte, error)

Marshal (generated function)

func (MissionAck) MarshalEasyJSON added in v1.5.0

func (v MissionAck) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MissionAck) MarshalJSON added in v1.5.0

func (v MissionAck) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MissionAck) MsgID

func (m *MissionAck) MsgID() message.MessageID

MsgID (generated function)

func (*MissionAck) String

func (m *MissionAck) String() string

String (generated function)

func (*MissionAck) Unmarshal

func (m *MissionAck) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MissionAck) UnmarshalEasyJSON added in v1.5.0

func (v *MissionAck) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MissionAck) UnmarshalJSON added in v1.5.0

func (v *MissionAck) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MissionChanged

type MissionChanged struct {
	StartIndex   int16            `json:"StartIndex" `   // Start index for partial mission change (-1 for all items).
	EndIndex     int16            `json:"EndIndex" `     // End index of a partial mission change. -1 is a synonym for the last mission item (i.e. selects all items from start_index). Ignore field if start_index=-1.
	OriginSysid  uint8            `json:"OriginSysid" `  // System ID of the author of the new mission.
	OriginCompid MAV_COMPONENT    `json:"OriginCompid" ` // Compnent ID of the author of the new mission.
	MissionType  MAV_MISSION_TYPE `json:"MissionType" `  // Mission type.
}

MissionChanged struct (generated typeinfo) A broadcast message to notify any ground station or SDK if a mission, geofence or safe points have changed on the vehicle.

func (*MissionChanged) Dict

func (m *MissionChanged) Dict() map[string]interface{}

ToMap (generated function)

func (*MissionChanged) Marshal

func (m *MissionChanged) Marshal() ([]byte, error)

Marshal (generated function)

func (MissionChanged) MarshalEasyJSON added in v1.5.0

func (v MissionChanged) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MissionChanged) MarshalJSON added in v1.5.0

func (v MissionChanged) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MissionChanged) MsgID

func (m *MissionChanged) MsgID() message.MessageID

MsgID (generated function)

func (*MissionChanged) String

func (m *MissionChanged) String() string

String (generated function)

func (*MissionChanged) Unmarshal

func (m *MissionChanged) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MissionChanged) UnmarshalEasyJSON added in v1.5.0

func (v *MissionChanged) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MissionChanged) UnmarshalJSON added in v1.5.0

func (v *MissionChanged) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MissionClearAll

type MissionClearAll struct {
	TargetSystem    uint8 `json:"TargetSystem" `    // System ID
	TargetComponent uint8 `json:"TargetComponent" ` // Component ID
}

MissionClearAll struct (generated typeinfo) Delete all mission items at once.

func (*MissionClearAll) Dict

func (m *MissionClearAll) Dict() map[string]interface{}

ToMap (generated function)

func (*MissionClearAll) Marshal

func (m *MissionClearAll) Marshal() ([]byte, error)

Marshal (generated function)

func (MissionClearAll) MarshalEasyJSON added in v1.5.0

func (v MissionClearAll) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MissionClearAll) MarshalJSON added in v1.5.0

func (v MissionClearAll) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MissionClearAll) MsgID

func (m *MissionClearAll) MsgID() message.MessageID

MsgID (generated function)

func (*MissionClearAll) String

func (m *MissionClearAll) String() string

String (generated function)

func (*MissionClearAll) Unmarshal

func (m *MissionClearAll) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MissionClearAll) UnmarshalEasyJSON added in v1.5.0

func (v *MissionClearAll) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MissionClearAll) UnmarshalJSON added in v1.5.0

func (v *MissionClearAll) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MissionCount

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

MissionCount struct (generated typeinfo) This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of waypoints.

func (*MissionCount) Dict

func (m *MissionCount) Dict() map[string]interface{}

ToMap (generated function)

func (*MissionCount) Marshal

func (m *MissionCount) Marshal() ([]byte, error)

Marshal (generated function)

func (MissionCount) MarshalEasyJSON added in v1.5.0

func (v MissionCount) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MissionCount) MarshalJSON added in v1.5.0

func (v MissionCount) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MissionCount) MsgID

func (m *MissionCount) MsgID() message.MessageID

MsgID (generated function)

func (*MissionCount) String

func (m *MissionCount) String() string

String (generated function)

func (*MissionCount) Unmarshal

func (m *MissionCount) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MissionCount) UnmarshalEasyJSON added in v1.5.0

func (v *MissionCount) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MissionCount) UnmarshalJSON added in v1.5.0

func (v *MissionCount) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MissionCurrent

type MissionCurrent struct {
	Seq uint16 `json:"Seq" ` // Sequence
}

MissionCurrent struct (generated typeinfo) Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item.

func (*MissionCurrent) Dict

func (m *MissionCurrent) Dict() map[string]interface{}

ToMap (generated function)

func (*MissionCurrent) Marshal

func (m *MissionCurrent) Marshal() ([]byte, error)

Marshal (generated function)

func (MissionCurrent) MarshalEasyJSON added in v1.5.0

func (v MissionCurrent) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MissionCurrent) MarshalJSON added in v1.5.0

func (v MissionCurrent) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MissionCurrent) MsgID

func (m *MissionCurrent) MsgID() message.MessageID

MsgID (generated function)

func (*MissionCurrent) String

func (m *MissionCurrent) String() string

String (generated function)

func (*MissionCurrent) Unmarshal

func (m *MissionCurrent) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MissionCurrent) UnmarshalEasyJSON added in v1.5.0

func (v *MissionCurrent) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MissionCurrent) UnmarshalJSON added in v1.5.0

func (v *MissionCurrent) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MissionItem

type MissionItem struct {
	Param1          float32   `json:"Param1" `          // PARAM1, see MAV_CMD enum
	Param2          float32   `json:"Param2" `          // PARAM2, see MAV_CMD enum
	Param3          float32   `json:"Param3" `          // PARAM3, see MAV_CMD enum
	Param4          float32   `json:"Param4" `          // PARAM4, see MAV_CMD enum
	X               float32   `json:"X" `               // PARAM5 / local: X coordinate, global: latitude
	Y               float32   `json:"Y" `               // PARAM6 / local: Y coordinate, global: longitude
	Z               float32   `json:"Z" `               // PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).
	Seq             uint16    `json:"Seq" `             // Sequence
	Command         MAV_CMD   `json:"Command" `         // The scheduled action for the waypoint.
	TargetSystem    uint8     `json:"TargetSystem" `    // System ID
	TargetComponent uint8     `json:"TargetComponent" ` // Component ID
	Frame           MAV_FRAME `json:"Frame" `           // The coordinate system of the waypoint.
	Current         uint8     `json:"Current" `         // false:0, true:1
	Autocontinue    uint8     `json:"Autocontinue" `    // Autocontinue to next waypoint
}

MissionItem struct (generated typeinfo) Message encoding a mission item. This message is emitted to announce

the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN may be used to indicate an optional/default value (e.g. to use the system's current latitude or yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html.

func (*MissionItem) Dict

func (m *MissionItem) Dict() map[string]interface{}

ToMap (generated function)

func (*MissionItem) Marshal

func (m *MissionItem) Marshal() ([]byte, error)

Marshal (generated function)

func (MissionItem) MarshalEasyJSON added in v1.5.0

func (v MissionItem) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MissionItem) MarshalJSON added in v1.5.0

func (v MissionItem) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MissionItem) MsgID

func (m *MissionItem) MsgID() message.MessageID

MsgID (generated function)

func (*MissionItem) String

func (m *MissionItem) String() string

String (generated function)

func (*MissionItem) Unmarshal

func (m *MissionItem) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MissionItem) UnmarshalEasyJSON added in v1.5.0

func (v *MissionItem) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MissionItem) UnmarshalJSON added in v1.5.0

func (v *MissionItem) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MissionItemInt

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

MissionItemInt struct (generated typeinfo) Message encoding a mission item. This message is emitted to announce

the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html.

func (*MissionItemInt) Dict

func (m *MissionItemInt) Dict() map[string]interface{}

ToMap (generated function)

func (*MissionItemInt) Marshal

func (m *MissionItemInt) Marshal() ([]byte, error)

Marshal (generated function)

func (MissionItemInt) MarshalEasyJSON added in v1.5.0

func (v MissionItemInt) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MissionItemInt) MarshalJSON added in v1.5.0

func (v MissionItemInt) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MissionItemInt) MsgID

func (m *MissionItemInt) MsgID() message.MessageID

MsgID (generated function)

func (*MissionItemInt) String

func (m *MissionItemInt) String() string

String (generated function)

func (*MissionItemInt) Unmarshal

func (m *MissionItemInt) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MissionItemInt) UnmarshalEasyJSON added in v1.5.0

func (v *MissionItemInt) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MissionItemInt) UnmarshalJSON added in v1.5.0

func (v *MissionItemInt) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MissionItemReached

type MissionItemReached struct {
	Seq uint16 `json:"Seq" ` // Sequence
}

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

func (*MissionItemReached) Dict

func (m *MissionItemReached) Dict() map[string]interface{}

ToMap (generated function)

func (*MissionItemReached) Marshal

func (m *MissionItemReached) Marshal() ([]byte, error)

Marshal (generated function)

func (MissionItemReached) MarshalEasyJSON added in v1.5.0

func (v MissionItemReached) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MissionItemReached) MarshalJSON added in v1.5.0

func (v MissionItemReached) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MissionItemReached) MsgID

MsgID (generated function)

func (*MissionItemReached) String

func (m *MissionItemReached) String() string

String (generated function)

func (*MissionItemReached) Unmarshal

func (m *MissionItemReached) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MissionItemReached) UnmarshalEasyJSON added in v1.5.0

func (v *MissionItemReached) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MissionItemReached) UnmarshalJSON added in v1.5.0

func (v *MissionItemReached) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MissionRequest

type MissionRequest struct {
	Seq             uint16 `json:"Seq" `             // Sequence
	TargetSystem    uint8  `json:"TargetSystem" `    // System ID
	TargetComponent uint8  `json:"TargetComponent" ` // Component ID
}

MissionRequest struct (generated typeinfo) Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. https://mavlink.io/en/services/mission.html

func (*MissionRequest) Dict

func (m *MissionRequest) Dict() map[string]interface{}

ToMap (generated function)

func (*MissionRequest) Marshal

func (m *MissionRequest) Marshal() ([]byte, error)

Marshal (generated function)

func (MissionRequest) MarshalEasyJSON added in v1.5.0

func (v MissionRequest) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MissionRequest) MarshalJSON added in v1.5.0

func (v MissionRequest) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MissionRequest) MsgID

func (m *MissionRequest) MsgID() message.MessageID

MsgID (generated function)

func (*MissionRequest) String

func (m *MissionRequest) String() string

String (generated function)

func (*MissionRequest) Unmarshal

func (m *MissionRequest) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MissionRequest) UnmarshalEasyJSON added in v1.5.0

func (v *MissionRequest) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MissionRequest) UnmarshalJSON added in v1.5.0

func (v *MissionRequest) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MissionRequestInt

type MissionRequestInt struct {
	Seq             uint16 `json:"Seq" `             // Sequence
	TargetSystem    uint8  `json:"TargetSystem" `    // System ID
	TargetComponent uint8  `json:"TargetComponent" ` // Component ID
}

MissionRequestInt struct (generated typeinfo) Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. https://mavlink.io/en/services/mission.html

func (*MissionRequestInt) Dict

func (m *MissionRequestInt) Dict() map[string]interface{}

ToMap (generated function)

func (*MissionRequestInt) Marshal

func (m *MissionRequestInt) Marshal() ([]byte, error)

Marshal (generated function)

func (MissionRequestInt) MarshalEasyJSON added in v1.5.0

func (v MissionRequestInt) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MissionRequestInt) MarshalJSON added in v1.5.0

func (v MissionRequestInt) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MissionRequestInt) MsgID

func (m *MissionRequestInt) MsgID() message.MessageID

MsgID (generated function)

func (*MissionRequestInt) String

func (m *MissionRequestInt) String() string

String (generated function)

func (*MissionRequestInt) Unmarshal

func (m *MissionRequestInt) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MissionRequestInt) UnmarshalEasyJSON added in v1.5.0

func (v *MissionRequestInt) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MissionRequestInt) UnmarshalJSON added in v1.5.0

func (v *MissionRequestInt) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MissionRequestList

type MissionRequestList struct {
	TargetSystem    uint8 `json:"TargetSystem" `    // System ID
	TargetComponent uint8 `json:"TargetComponent" ` // Component ID
}

MissionRequestList struct (generated typeinfo) Request the overall list of mission items from the system/component.

func (*MissionRequestList) Dict

func (m *MissionRequestList) Dict() map[string]interface{}

ToMap (generated function)

func (*MissionRequestList) Marshal

func (m *MissionRequestList) Marshal() ([]byte, error)

Marshal (generated function)

func (MissionRequestList) MarshalEasyJSON added in v1.5.0

func (v MissionRequestList) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MissionRequestList) MarshalJSON added in v1.5.0

func (v MissionRequestList) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MissionRequestList) MsgID

MsgID (generated function)

func (*MissionRequestList) String

func (m *MissionRequestList) String() string

String (generated function)

func (*MissionRequestList) Unmarshal

func (m *MissionRequestList) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MissionRequestList) UnmarshalEasyJSON added in v1.5.0

func (v *MissionRequestList) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MissionRequestList) UnmarshalJSON added in v1.5.0

func (v *MissionRequestList) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MissionRequestPartialList

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

MissionRequestPartialList struct (generated typeinfo) Request a partial list of mission items from the system/component. https://mavlink.io/en/services/mission.html. If start and end index are the same, just send one waypoint.

func (*MissionRequestPartialList) Dict

func (m *MissionRequestPartialList) Dict() map[string]interface{}

ToMap (generated function)

func (*MissionRequestPartialList) Marshal

func (m *MissionRequestPartialList) Marshal() ([]byte, error)

Marshal (generated function)

func (MissionRequestPartialList) MarshalEasyJSON added in v1.5.0

func (v MissionRequestPartialList) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MissionRequestPartialList) MarshalJSON added in v1.5.0

func (v MissionRequestPartialList) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MissionRequestPartialList) MsgID

MsgID (generated function)

func (*MissionRequestPartialList) String

func (m *MissionRequestPartialList) String() string

String (generated function)

func (*MissionRequestPartialList) Unmarshal

func (m *MissionRequestPartialList) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MissionRequestPartialList) UnmarshalEasyJSON added in v1.5.0

func (v *MissionRequestPartialList) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MissionRequestPartialList) UnmarshalJSON added in v1.5.0

func (v *MissionRequestPartialList) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MissionSetCurrent

type MissionSetCurrent struct {
	Seq             uint16 `json:"Seq" `             // Sequence
	TargetSystem    uint8  `json:"TargetSystem" `    // System ID
	TargetComponent uint8  `json:"TargetComponent" ` // Component ID
}

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

func (*MissionSetCurrent) Dict

func (m *MissionSetCurrent) Dict() map[string]interface{}

ToMap (generated function)

func (*MissionSetCurrent) Marshal

func (m *MissionSetCurrent) Marshal() ([]byte, error)

Marshal (generated function)

func (MissionSetCurrent) MarshalEasyJSON added in v1.5.0

func (v MissionSetCurrent) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MissionSetCurrent) MarshalJSON added in v1.5.0

func (v MissionSetCurrent) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MissionSetCurrent) MsgID

func (m *MissionSetCurrent) MsgID() message.MessageID

MsgID (generated function)

func (*MissionSetCurrent) String

func (m *MissionSetCurrent) String() string

String (generated function)

func (*MissionSetCurrent) Unmarshal

func (m *MissionSetCurrent) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MissionSetCurrent) UnmarshalEasyJSON added in v1.5.0

func (v *MissionSetCurrent) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MissionSetCurrent) UnmarshalJSON added in v1.5.0

func (v *MissionSetCurrent) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MissionWritePartialList

type MissionWritePartialList struct {
	StartIndex      int16 `json:"StartIndex" `      // Start index. Must be smaller / equal to the largest index of the current onboard list.
	EndIndex        int16 `json:"EndIndex" `        // End index, equal or greater than start index.
	TargetSystem    uint8 `json:"TargetSystem" `    // System ID
	TargetComponent uint8 `json:"TargetComponent" ` // Component ID
}

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

func (*MissionWritePartialList) Dict

func (m *MissionWritePartialList) Dict() map[string]interface{}

ToMap (generated function)

func (*MissionWritePartialList) Marshal

func (m *MissionWritePartialList) Marshal() ([]byte, error)

Marshal (generated function)

func (MissionWritePartialList) MarshalEasyJSON added in v1.5.0

func (v MissionWritePartialList) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MissionWritePartialList) MarshalJSON added in v1.5.0

func (v MissionWritePartialList) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MissionWritePartialList) MsgID

MsgID (generated function)

func (*MissionWritePartialList) String

func (m *MissionWritePartialList) String() string

String (generated function)

func (*MissionWritePartialList) Unmarshal

func (m *MissionWritePartialList) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MissionWritePartialList) UnmarshalEasyJSON added in v1.5.0

func (v *MissionWritePartialList) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MissionWritePartialList) UnmarshalJSON added in v1.5.0

func (v *MissionWritePartialList) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MountConfigure

type MountConfigure struct {
	TargetSystem    uint8          `json:"TargetSystem" `    // System ID.
	TargetComponent uint8          `json:"TargetComponent" ` // Component ID.
	MountMode       MAV_MOUNT_MODE `json:"MountMode" `       // Mount operating mode.
	StabRoll        uint8          `json:"StabRoll" `        // (1 = yes, 0 = no).
	StabPitch       uint8          `json:"StabPitch" `       // (1 = yes, 0 = no).
	StabYaw         uint8          `json:"StabYaw" `         // (1 = yes, 0 = no).
}

MountConfigure struct (generated typeinfo) Message to configure a camera mount, directional antenna, etc.

func (*MountConfigure) Dict

func (m *MountConfigure) Dict() map[string]interface{}

ToMap (generated function)

func (*MountConfigure) Marshal

func (m *MountConfigure) Marshal() ([]byte, error)

Marshal (generated function)

func (MountConfigure) MarshalEasyJSON added in v1.5.0

func (v MountConfigure) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MountConfigure) MarshalJSON added in v1.5.0

func (v MountConfigure) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MountConfigure) MsgID

func (m *MountConfigure) MsgID() message.MessageID

MsgID (generated function)

func (*MountConfigure) String

func (m *MountConfigure) String() string

String (generated function)

func (*MountConfigure) Unmarshal

func (m *MountConfigure) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MountConfigure) UnmarshalEasyJSON added in v1.5.0

func (v *MountConfigure) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MountConfigure) UnmarshalJSON added in v1.5.0

func (v *MountConfigure) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MountControl

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

MountControl struct (generated typeinfo) Message to control a camera mount, directional antenna, etc.

func (*MountControl) Dict

func (m *MountControl) Dict() map[string]interface{}

ToMap (generated function)

func (*MountControl) Marshal

func (m *MountControl) Marshal() ([]byte, error)

Marshal (generated function)

func (MountControl) MarshalEasyJSON added in v1.5.0

func (v MountControl) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MountControl) MarshalJSON added in v1.5.0

func (v MountControl) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MountControl) MsgID

func (m *MountControl) MsgID() message.MessageID

MsgID (generated function)

func (*MountControl) String

func (m *MountControl) String() string

String (generated function)

func (*MountControl) Unmarshal

func (m *MountControl) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MountControl) UnmarshalEasyJSON added in v1.5.0

func (v *MountControl) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MountControl) UnmarshalJSON added in v1.5.0

func (v *MountControl) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type MountStatus

type MountStatus struct {
	PointingA       int32 `json:"PointingA" `       // [ cdeg ] Pitch.
	PointingB       int32 `json:"PointingB" `       // [ cdeg ] Roll.
	PointingC       int32 `json:"PointingC" `       // [ cdeg ] Yaw.
	TargetSystem    uint8 `json:"TargetSystem" `    // System ID.
	TargetComponent uint8 `json:"TargetComponent" ` // Component ID.
}

MountStatus struct (generated typeinfo) Message with some status from APM to GCS about camera or antenna mount.

func (*MountStatus) Dict

func (m *MountStatus) Dict() map[string]interface{}

ToMap (generated function)

func (*MountStatus) Marshal

func (m *MountStatus) Marshal() ([]byte, error)

Marshal (generated function)

func (MountStatus) MarshalEasyJSON added in v1.5.0

func (v MountStatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (MountStatus) MarshalJSON added in v1.5.0

func (v MountStatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*MountStatus) MsgID

func (m *MountStatus) MsgID() message.MessageID

MsgID (generated function)

func (*MountStatus) String

func (m *MountStatus) String() string

String (generated function)

func (*MountStatus) Unmarshal

func (m *MountStatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*MountStatus) UnmarshalEasyJSON added in v1.5.0

func (v *MountStatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*MountStatus) UnmarshalJSON added in v1.5.0

func (v *MountStatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type NamedValueFloat

type NamedValueFloat struct {
	TimeBootMs uint32  `json:"TimeBootMs" `    // [ ms ] Timestamp (time since system boot).
	Value      float32 `json:"Value" `         // Floating point value
	Name       string  `json:"Name" len:"10" ` // Name of the debug variable
}

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

func (*NamedValueFloat) Dict

func (m *NamedValueFloat) Dict() map[string]interface{}

ToMap (generated function)

func (*NamedValueFloat) Marshal

func (m *NamedValueFloat) Marshal() ([]byte, error)

Marshal (generated function)

func (NamedValueFloat) MarshalEasyJSON added in v1.5.0

func (v NamedValueFloat) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (NamedValueFloat) MarshalJSON added in v1.5.0

func (v NamedValueFloat) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*NamedValueFloat) MsgID

func (m *NamedValueFloat) MsgID() message.MessageID

MsgID (generated function)

func (*NamedValueFloat) String

func (m *NamedValueFloat) String() string

String (generated function)

func (*NamedValueFloat) Unmarshal

func (m *NamedValueFloat) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*NamedValueFloat) UnmarshalEasyJSON added in v1.5.0

func (v *NamedValueFloat) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*NamedValueFloat) UnmarshalJSON added in v1.5.0

func (v *NamedValueFloat) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type NamedValueInt

type NamedValueInt struct {
	TimeBootMs uint32 `json:"TimeBootMs" `    // [ ms ] Timestamp (time since system boot).
	Value      int32  `json:"Value" `         // Signed integer value
	Name       string `json:"Name" len:"10" ` // Name of the debug variable
}

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

func (*NamedValueInt) Dict

func (m *NamedValueInt) Dict() map[string]interface{}

ToMap (generated function)

func (*NamedValueInt) Marshal

func (m *NamedValueInt) Marshal() ([]byte, error)

Marshal (generated function)

func (NamedValueInt) MarshalEasyJSON added in v1.5.0

func (v NamedValueInt) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (NamedValueInt) MarshalJSON added in v1.5.0

func (v NamedValueInt) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*NamedValueInt) MsgID

func (m *NamedValueInt) MsgID() message.MessageID

MsgID (generated function)

func (*NamedValueInt) String

func (m *NamedValueInt) String() string

String (generated function)

func (*NamedValueInt) Unmarshal

func (m *NamedValueInt) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*NamedValueInt) UnmarshalEasyJSON added in v1.5.0

func (v *NamedValueInt) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*NamedValueInt) UnmarshalJSON added in v1.5.0

func (v *NamedValueInt) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type NavControllerOutput struct {
	NavRoll       float32 `json:"NavRoll" `       // [ deg ] Current desired roll
	NavPitch      float32 `json:"NavPitch" `      // [ deg ] Current desired pitch
	AltError      float32 `json:"AltError" `      // [ m ] Current altitude error
	AspdError     float32 `json:"AspdError" `     // [ m/s ] Current airspeed error
	XtrackError   float32 `json:"XtrackError" `   // [ m ] Current crosstrack error on x-y plane
	NavBearing    int16   `json:"NavBearing" `    // [ deg ] Current desired heading
	TargetBearing int16   `json:"TargetBearing" ` // [ deg ] Bearing to current waypoint/target
	WpDist        uint16  `json:"WpDist" `        // [ m ] Distance to active waypoint
}

NavControllerOutput struct (generated typeinfo) The state of the fixed wing navigation and position controller.

func (m *NavControllerOutput) Dict() map[string]interface{}

ToMap (generated function)

func (m *NavControllerOutput) Marshal() ([]byte, error)

Marshal (generated function)

func (v NavControllerOutput) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (v NavControllerOutput) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

MsgID (generated function)

func (m *NavControllerOutput) String() string

String (generated function)

func (m *NavControllerOutput) Unmarshal(data []byte) error

Unmarshal (generated function)

func (v *NavControllerOutput) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (v *NavControllerOutput) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type NavFilterBias struct {
	Usec   uint64  `json:"Usec" `   // Timestamp (microseconds)
	Accel0 float32 `json:"Accel0" ` // b_f[0]
	Accel1 float32 `json:"Accel1" ` // b_f[1]
	Accel2 float32 `json:"Accel2" ` // b_f[2]
	Gyro0  float32 `json:"Gyro0" `  // b_f[0]
	Gyro1  float32 `json:"Gyro1" `  // b_f[1]
	Gyro2  float32 `json:"Gyro2" `  // b_f[2]
}

NavFilterBias struct (generated typeinfo) Accelerometer and Gyro biases from the navigation filter

func (m *NavFilterBias) Dict() map[string]interface{}

ToMap (generated function)

func (m *NavFilterBias) Marshal() ([]byte, error)

Marshal (generated function)

func (v NavFilterBias) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (v NavFilterBias) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (m *NavFilterBias) MsgID() message.MessageID

MsgID (generated function)

func (m *NavFilterBias) String() string

String (generated function)

func (m *NavFilterBias) Unmarshal(data []byte) error

Unmarshal (generated function)

func (v *NavFilterBias) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (v *NavFilterBias) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ORBIT_YAW_BEHAVIOUR

type ORBIT_YAW_BEHAVIOUR int

ORBIT_YAW_BEHAVIOUR type. Yaw behaviour during orbit flight.

const (
	// ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER enum. Vehicle front points to the center (default)
	ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER ORBIT_YAW_BEHAVIOUR = 0
	// ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING enum. Vehicle front holds heading when message received
	ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING ORBIT_YAW_BEHAVIOUR = 1
	// ORBIT_YAW_BEHAVIOUR_UNCONTROLLED enum. Yaw uncontrolled
	ORBIT_YAW_BEHAVIOUR_UNCONTROLLED ORBIT_YAW_BEHAVIOUR = 2
	// ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE enum. Vehicle front follows flight path (tangential to circle)
	ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE ORBIT_YAW_BEHAVIOUR = 3
	// ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED enum. Yaw controlled by RC input
	ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED ORBIT_YAW_BEHAVIOUR = 4
)

func (ORBIT_YAW_BEHAVIOUR) Bitmask

func (e ORBIT_YAW_BEHAVIOUR) Bitmask() string

Bitmask return string representetion of intersects ORBIT_YAW_BEHAVIOUR enums

func (ORBIT_YAW_BEHAVIOUR) MarshalBinary

func (e ORBIT_YAW_BEHAVIOUR) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (ORBIT_YAW_BEHAVIOUR) String

func (e ORBIT_YAW_BEHAVIOUR) String() string

func (*ORBIT_YAW_BEHAVIOUR) UnmarshalBinary

func (e *ORBIT_YAW_BEHAVIOUR) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type OSD_PARAM_CONFIG_ERROR

type OSD_PARAM_CONFIG_ERROR int

OSD_PARAM_CONFIG_ERROR type. The error type for the OSD parameter editor.

const (
	// OSD_PARAM_SUCCESS enum
	OSD_PARAM_SUCCESS OSD_PARAM_CONFIG_ERROR = 0
	// OSD_PARAM_INVALID_SCREEN enum
	OSD_PARAM_INVALID_SCREEN OSD_PARAM_CONFIG_ERROR = 1
	// OSD_PARAM_INVALID_PARAMETER_INDEX enum
	OSD_PARAM_INVALID_PARAMETER_INDEX OSD_PARAM_CONFIG_ERROR = 2
	// OSD_PARAM_INVALID_PARAMETER enum
	OSD_PARAM_INVALID_PARAMETER OSD_PARAM_CONFIG_ERROR = 3
)

func (OSD_PARAM_CONFIG_ERROR) Bitmask

func (e OSD_PARAM_CONFIG_ERROR) Bitmask() string

Bitmask return string representetion of intersects OSD_PARAM_CONFIG_ERROR enums

func (OSD_PARAM_CONFIG_ERROR) MarshalBinary

func (e OSD_PARAM_CONFIG_ERROR) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (OSD_PARAM_CONFIG_ERROR) String

func (e OSD_PARAM_CONFIG_ERROR) String() string

func (*OSD_PARAM_CONFIG_ERROR) UnmarshalBinary

func (e *OSD_PARAM_CONFIG_ERROR) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type OSD_PARAM_CONFIG_TYPE

type OSD_PARAM_CONFIG_TYPE int

OSD_PARAM_CONFIG_TYPE type. The type of parameter for the OSD parameter editor.

const (
	// OSD_PARAM_NONE enum
	OSD_PARAM_NONE OSD_PARAM_CONFIG_TYPE = 0
	// OSD_PARAM_SERIAL_PROTOCOL enum
	OSD_PARAM_SERIAL_PROTOCOL OSD_PARAM_CONFIG_TYPE = 1
	// OSD_PARAM_SERVO_FUNCTION enum
	OSD_PARAM_SERVO_FUNCTION OSD_PARAM_CONFIG_TYPE = 2
	// OSD_PARAM_AUX_FUNCTION enum
	OSD_PARAM_AUX_FUNCTION OSD_PARAM_CONFIG_TYPE = 3
	// OSD_PARAM_FLIGHT_MODE enum
	OSD_PARAM_FLIGHT_MODE OSD_PARAM_CONFIG_TYPE = 4
	// OSD_PARAM_FAILSAFE_ACTION enum
	OSD_PARAM_FAILSAFE_ACTION OSD_PARAM_CONFIG_TYPE = 5
	// OSD_PARAM_FAILSAFE_ACTION_1 enum
	OSD_PARAM_FAILSAFE_ACTION_1 OSD_PARAM_CONFIG_TYPE = 6
	// OSD_PARAM_FAILSAFE_ACTION_2 enum
	OSD_PARAM_FAILSAFE_ACTION_2 OSD_PARAM_CONFIG_TYPE = 7
	// OSD_PARAM_NUM_TYPES enum
	OSD_PARAM_NUM_TYPES OSD_PARAM_CONFIG_TYPE = 8
)

func (OSD_PARAM_CONFIG_TYPE) Bitmask

func (e OSD_PARAM_CONFIG_TYPE) Bitmask() string

Bitmask return string representetion of intersects OSD_PARAM_CONFIG_TYPE enums

func (OSD_PARAM_CONFIG_TYPE) MarshalBinary

func (e OSD_PARAM_CONFIG_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (OSD_PARAM_CONFIG_TYPE) String

func (e OSD_PARAM_CONFIG_TYPE) String() string

func (*OSD_PARAM_CONFIG_TYPE) UnmarshalBinary

func (e *OSD_PARAM_CONFIG_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type OpticalFlow

type OpticalFlow struct {
	TimeUsec       uint64  `json:"TimeUsec" `       // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	FlowCompMX     float32 `json:"FlowCompMX" `     // [ m/s ] Flow in x-sensor direction, angular-speed compensated
	FlowCompMY     float32 `json:"FlowCompMY" `     // [ m/s ] Flow in y-sensor direction, angular-speed compensated
	GroundDistance float32 `json:"GroundDistance" ` // [ m ] Ground distance. Positive value: distance known. Negative value: Unknown distance
	FlowX          int16   `json:"FlowX" `          // [ dpix ] Flow in x-sensor direction
	FlowY          int16   `json:"FlowY" `          // [ dpix ] Flow in y-sensor direction
	SensorID       uint8   `json:"SensorID" `       // Sensor ID
	Quality        uint8   `json:"Quality" `        // Optical flow quality / confidence. 0: bad, 255: maximum quality
}

OpticalFlow struct (generated typeinfo) Optical flow from a flow sensor (e.g. optical mouse sensor)

func (*OpticalFlow) Dict

func (m *OpticalFlow) Dict() map[string]interface{}

ToMap (generated function)

func (*OpticalFlow) Marshal

func (m *OpticalFlow) Marshal() ([]byte, error)

Marshal (generated function)

func (OpticalFlow) MarshalEasyJSON added in v1.5.0

func (v OpticalFlow) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (OpticalFlow) MarshalJSON added in v1.5.0

func (v OpticalFlow) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*OpticalFlow) MsgID

func (m *OpticalFlow) MsgID() message.MessageID

MsgID (generated function)

func (*OpticalFlow) String

func (m *OpticalFlow) String() string

String (generated function)

func (*OpticalFlow) Unmarshal

func (m *OpticalFlow) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*OpticalFlow) UnmarshalEasyJSON added in v1.5.0

func (v *OpticalFlow) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*OpticalFlow) UnmarshalJSON added in v1.5.0

func (v *OpticalFlow) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type OpticalFlowRad

type OpticalFlowRad struct {
	TimeUsec            uint64  `json:"TimeUsec" `            // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	IntegrationTimeUs   uint32  `json:"IntegrationTimeUs" `   // [ us ] Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
	IntegratedX         float32 `json:"IntegratedX" `         // [ rad ] Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
	IntegratedY         float32 `json:"IntegratedY" `         // [ rad ] Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
	IntegratedXgyro     float32 `json:"IntegratedXgyro" `     // [ rad ] RH rotation around X axis
	IntegratedYgyro     float32 `json:"IntegratedYgyro" `     // [ rad ] RH rotation around Y axis
	IntegratedZgyro     float32 `json:"IntegratedZgyro" `     // [ rad ] RH rotation around Z axis
	TimeDeltaDistanceUs uint32  `json:"TimeDeltaDistanceUs" ` // [ us ] Time since the distance was sampled.
	Distance            float32 `json:"Distance" `            // [ m ] Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
	Temperature         int16   `json:"Temperature" `         // [ cdegC ] Temperature
	SensorID            uint8   `json:"SensorID" `            // Sensor ID
	Quality             uint8   `json:"Quality" `             // Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
}

OpticalFlowRad struct (generated typeinfo) Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor)

func (*OpticalFlowRad) Dict

func (m *OpticalFlowRad) Dict() map[string]interface{}

ToMap (generated function)

func (*OpticalFlowRad) Marshal

func (m *OpticalFlowRad) Marshal() ([]byte, error)

Marshal (generated function)

func (OpticalFlowRad) MarshalEasyJSON added in v1.5.0

func (v OpticalFlowRad) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (OpticalFlowRad) MarshalJSON added in v1.5.0

func (v OpticalFlowRad) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*OpticalFlowRad) MsgID

func (m *OpticalFlowRad) MsgID() message.MessageID

MsgID (generated function)

func (*OpticalFlowRad) String

func (m *OpticalFlowRad) String() string

String (generated function)

func (*OpticalFlowRad) Unmarshal

func (m *OpticalFlowRad) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*OpticalFlowRad) UnmarshalEasyJSON added in v1.5.0

func (v *OpticalFlowRad) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*OpticalFlowRad) UnmarshalJSON added in v1.5.0

func (v *OpticalFlowRad) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type PARACHUTE_ACTION

type PARACHUTE_ACTION int

PARACHUTE_ACTION type. Parachute actions. Trigger release and enable/disable auto-release.

const (
	// PARACHUTE_DISABLE enum. Disable auto-release of parachute (i.e. release triggered by crash detectors)
	PARACHUTE_DISABLE PARACHUTE_ACTION = 0
	// PARACHUTE_ENABLE enum. Enable auto-release of parachute
	PARACHUTE_ENABLE PARACHUTE_ACTION = 1
	// PARACHUTE_RELEASE enum. Release parachute and kill motors
	PARACHUTE_RELEASE PARACHUTE_ACTION = 2
)

func (PARACHUTE_ACTION) Bitmask

func (e PARACHUTE_ACTION) Bitmask() string

Bitmask return string representetion of intersects PARACHUTE_ACTION enums

func (PARACHUTE_ACTION) MarshalBinary

func (e PARACHUTE_ACTION) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (PARACHUTE_ACTION) String

func (e PARACHUTE_ACTION) String() string

func (*PARACHUTE_ACTION) UnmarshalBinary

func (e *PARACHUTE_ACTION) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type PARAM_ACK

type PARAM_ACK int

PARAM_ACK type. Result from PARAM_EXT_SET message (or a PARAM_SET within a transaction).

const (
	// PARAM_ACK_ACCEPTED enum. Parameter value ACCEPTED and SET
	PARAM_ACK_ACCEPTED PARAM_ACK = 0
	// PARAM_ACK_VALUE_UNSUPPORTED enum. Parameter value UNKNOWN/UNSUPPORTED
	PARAM_ACK_VALUE_UNSUPPORTED PARAM_ACK = 1
	// PARAM_ACK_FAILED enum. Parameter failed to set
	PARAM_ACK_FAILED PARAM_ACK = 2
	// PARAM_ACK_IN_PROGRESS enum. Parameter value received but not yet set/accepted. A subsequent PARAM_ACK_TRANSACTION or PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating taht the the parameter was recieved and does not need to be resent
	PARAM_ACK_IN_PROGRESS PARAM_ACK = 3
)

func (PARAM_ACK) Bitmask

func (e PARAM_ACK) Bitmask() string

Bitmask return string representetion of intersects PARAM_ACK enums

func (PARAM_ACK) MarshalBinary

func (e PARAM_ACK) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (PARAM_ACK) String

func (e PARAM_ACK) String() string

func (*PARAM_ACK) UnmarshalBinary

func (e *PARAM_ACK) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type PARAM_TRANSACTION_ACTION

type PARAM_TRANSACTION_ACTION int

PARAM_TRANSACTION_ACTION type. Possible parameter transaction actions.

const (
	// PARAM_TRANSACTION_ACTION_START enum. Commit the current parameter transaction
	PARAM_TRANSACTION_ACTION_START PARAM_TRANSACTION_ACTION = 0
	// PARAM_TRANSACTION_ACTION_COMMIT enum. Commit the current parameter transaction
	PARAM_TRANSACTION_ACTION_COMMIT PARAM_TRANSACTION_ACTION = 1
	// PARAM_TRANSACTION_ACTION_CANCEL enum. Cancel the current parameter transaction
	PARAM_TRANSACTION_ACTION_CANCEL PARAM_TRANSACTION_ACTION = 2
)

func (PARAM_TRANSACTION_ACTION) Bitmask

func (e PARAM_TRANSACTION_ACTION) Bitmask() string

Bitmask return string representetion of intersects PARAM_TRANSACTION_ACTION enums

func (PARAM_TRANSACTION_ACTION) MarshalBinary

func (e PARAM_TRANSACTION_ACTION) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (PARAM_TRANSACTION_ACTION) String

func (e PARAM_TRANSACTION_ACTION) String() string

func (*PARAM_TRANSACTION_ACTION) UnmarshalBinary

func (e *PARAM_TRANSACTION_ACTION) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type PARAM_TRANSACTION_TRANSPORT

type PARAM_TRANSACTION_TRANSPORT int

PARAM_TRANSACTION_TRANSPORT type. Possible transport layers to set and get parameters via mavlink during a parameter transaction.

const (
	// PARAM_TRANSACTION_TRANSPORT_PARAM enum. Transaction over param transport
	PARAM_TRANSACTION_TRANSPORT_PARAM PARAM_TRANSACTION_TRANSPORT = 0
	// PARAM_TRANSACTION_TRANSPORT_PARAM_EXT enum. Transaction over param_ext transport
	PARAM_TRANSACTION_TRANSPORT_PARAM_EXT PARAM_TRANSACTION_TRANSPORT = 1
)

func (PARAM_TRANSACTION_TRANSPORT) Bitmask

func (e PARAM_TRANSACTION_TRANSPORT) Bitmask() string

Bitmask return string representetion of intersects PARAM_TRANSACTION_TRANSPORT enums

func (PARAM_TRANSACTION_TRANSPORT) MarshalBinary

func (e PARAM_TRANSACTION_TRANSPORT) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (PARAM_TRANSACTION_TRANSPORT) String

func (*PARAM_TRANSACTION_TRANSPORT) UnmarshalBinary

func (e *PARAM_TRANSACTION_TRANSPORT) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type PID_TUNING_AXIS

type PID_TUNING_AXIS int

PID_TUNING_AXIS type

const (
	// PID_TUNING_ROLL enum
	PID_TUNING_ROLL PID_TUNING_AXIS = 1
	// PID_TUNING_PITCH enum
	PID_TUNING_PITCH PID_TUNING_AXIS = 2
	// PID_TUNING_YAW enum
	PID_TUNING_YAW PID_TUNING_AXIS = 3
	// PID_TUNING_ACCZ enum
	PID_TUNING_ACCZ PID_TUNING_AXIS = 4
	// PID_TUNING_STEER enum
	PID_TUNING_STEER PID_TUNING_AXIS = 5
	// PID_TUNING_LANDING enum
	PID_TUNING_LANDING PID_TUNING_AXIS = 6
)

func (PID_TUNING_AXIS) Bitmask

func (e PID_TUNING_AXIS) Bitmask() string

Bitmask return string representetion of intersects PID_TUNING_AXIS enums

func (PID_TUNING_AXIS) MarshalBinary

func (e PID_TUNING_AXIS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (PID_TUNING_AXIS) String

func (e PID_TUNING_AXIS) String() string

func (*PID_TUNING_AXIS) UnmarshalBinary

func (e *PID_TUNING_AXIS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type PLANE_MODE

type PLANE_MODE int

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

const (
	// PLANE_MODE_MANUAL enum
	PLANE_MODE_MANUAL PLANE_MODE = 0
	// PLANE_MODE_CIRCLE enum
	PLANE_MODE_CIRCLE PLANE_MODE = 1
	// PLANE_MODE_STABILIZE enum
	PLANE_MODE_STABILIZE PLANE_MODE = 2
	// PLANE_MODE_TRAINING enum
	PLANE_MODE_TRAINING PLANE_MODE = 3
	// PLANE_MODE_ACRO enum
	PLANE_MODE_ACRO PLANE_MODE = 4
	// PLANE_MODE_FLY_BY_WIRE_A enum
	PLANE_MODE_FLY_BY_WIRE_A PLANE_MODE = 5
	// PLANE_MODE_FLY_BY_WIRE_B enum
	PLANE_MODE_FLY_BY_WIRE_B PLANE_MODE = 6
	// PLANE_MODE_CRUISE enum
	PLANE_MODE_CRUISE PLANE_MODE = 7
	// PLANE_MODE_AUTOTUNE enum
	PLANE_MODE_AUTOTUNE PLANE_MODE = 8
	// PLANE_MODE_AUTO enum
	PLANE_MODE_AUTO PLANE_MODE = 10
	// PLANE_MODE_RTL enum
	PLANE_MODE_RTL PLANE_MODE = 11
	// PLANE_MODE_LOITER enum
	PLANE_MODE_LOITER PLANE_MODE = 12
	// PLANE_MODE_TAKEOFF enum
	PLANE_MODE_TAKEOFF PLANE_MODE = 13
	// PLANE_MODE_AVOID_ADSB enum
	PLANE_MODE_AVOID_ADSB PLANE_MODE = 14
	// PLANE_MODE_GUIDED enum
	PLANE_MODE_GUIDED PLANE_MODE = 15
	// PLANE_MODE_INITIALIZING enum
	PLANE_MODE_INITIALIZING PLANE_MODE = 16
	// PLANE_MODE_QSTABILIZE enum
	PLANE_MODE_QSTABILIZE PLANE_MODE = 17
	// PLANE_MODE_QHOVER enum
	PLANE_MODE_QHOVER PLANE_MODE = 18
	// PLANE_MODE_QLOITER enum
	PLANE_MODE_QLOITER PLANE_MODE = 19
	// PLANE_MODE_QLAND enum
	PLANE_MODE_QLAND PLANE_MODE = 20
	// PLANE_MODE_QRTL enum
	PLANE_MODE_QRTL PLANE_MODE = 21
	// PLANE_MODE_QAUTOTUNE enum
	PLANE_MODE_QAUTOTUNE PLANE_MODE = 22
	// PLANE_MODE_QACRO enum
	PLANE_MODE_QACRO PLANE_MODE = 23
	// PLANE_MODE_THERMAL enum
	PLANE_MODE_THERMAL PLANE_MODE = 24
)

func (PLANE_MODE) Bitmask

func (e PLANE_MODE) Bitmask() string

Bitmask return string representetion of intersects PLANE_MODE enums

func (PLANE_MODE) MarshalBinary

func (e PLANE_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (PLANE_MODE) String

func (e PLANE_MODE) String() string

func (*PLANE_MODE) UnmarshalBinary

func (e *PLANE_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type POSITION_TARGET_TYPEMASK

type POSITION_TARGET_TYPEMASK int

POSITION_TARGET_TYPEMASK type. Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration.

const (
	// POSITION_TARGET_TYPEMASK_X_IGNORE enum. Ignore position x
	POSITION_TARGET_TYPEMASK_X_IGNORE POSITION_TARGET_TYPEMASK = 1
	// POSITION_TARGET_TYPEMASK_Y_IGNORE enum. Ignore position y
	POSITION_TARGET_TYPEMASK_Y_IGNORE POSITION_TARGET_TYPEMASK = 2
	// POSITION_TARGET_TYPEMASK_Z_IGNORE enum. Ignore position z
	POSITION_TARGET_TYPEMASK_Z_IGNORE POSITION_TARGET_TYPEMASK = 4
	// POSITION_TARGET_TYPEMASK_VX_IGNORE enum. Ignore velocity x
	POSITION_TARGET_TYPEMASK_VX_IGNORE POSITION_TARGET_TYPEMASK = 8
	// POSITION_TARGET_TYPEMASK_VY_IGNORE enum. Ignore velocity y
	POSITION_TARGET_TYPEMASK_VY_IGNORE POSITION_TARGET_TYPEMASK = 16
	// POSITION_TARGET_TYPEMASK_VZ_IGNORE enum. Ignore velocity z
	POSITION_TARGET_TYPEMASK_VZ_IGNORE POSITION_TARGET_TYPEMASK = 32
	// POSITION_TARGET_TYPEMASK_AX_IGNORE enum. Ignore acceleration x
	POSITION_TARGET_TYPEMASK_AX_IGNORE POSITION_TARGET_TYPEMASK = 64
	// POSITION_TARGET_TYPEMASK_AY_IGNORE enum. Ignore acceleration y
	POSITION_TARGET_TYPEMASK_AY_IGNORE POSITION_TARGET_TYPEMASK = 128
	// POSITION_TARGET_TYPEMASK_AZ_IGNORE enum. Ignore acceleration z
	POSITION_TARGET_TYPEMASK_AZ_IGNORE POSITION_TARGET_TYPEMASK = 256
	// POSITION_TARGET_TYPEMASK_FORCE_SET enum. Use force instead of acceleration
	POSITION_TARGET_TYPEMASK_FORCE_SET POSITION_TARGET_TYPEMASK = 512
	// POSITION_TARGET_TYPEMASK_YAW_IGNORE enum. Ignore yaw
	POSITION_TARGET_TYPEMASK_YAW_IGNORE POSITION_TARGET_TYPEMASK = 1024
	// POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE enum. Ignore yaw rate
	POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE POSITION_TARGET_TYPEMASK = 2048
)

func (POSITION_TARGET_TYPEMASK) Bitmask

func (e POSITION_TARGET_TYPEMASK) Bitmask() string

Bitmask return string representetion of intersects POSITION_TARGET_TYPEMASK enums

func (POSITION_TARGET_TYPEMASK) MarshalBinary

func (e POSITION_TARGET_TYPEMASK) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (POSITION_TARGET_TYPEMASK) String

func (e POSITION_TARGET_TYPEMASK) String() string

func (*POSITION_TARGET_TYPEMASK) UnmarshalBinary

func (e *POSITION_TARGET_TYPEMASK) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type PRECISION_LAND_MODE

type PRECISION_LAND_MODE int

PRECISION_LAND_MODE type. Precision land modes (used in MAV_CMD_NAV_LAND).

const (
	// PRECISION_LAND_MODE_DISABLED enum. Normal (non-precision) landing
	PRECISION_LAND_MODE_DISABLED PRECISION_LAND_MODE = 0
	// PRECISION_LAND_MODE_OPPORTUNISTIC enum. Use precision landing if beacon detected when land command accepted, otherwise land normally
	PRECISION_LAND_MODE_OPPORTUNISTIC PRECISION_LAND_MODE = 1
	// PRECISION_LAND_MODE_REQUIRED enum. Use precision landing, searching for beacon if not found when land command accepted (land normally if beacon cannot be found)
	PRECISION_LAND_MODE_REQUIRED PRECISION_LAND_MODE = 2
)

func (PRECISION_LAND_MODE) Bitmask

func (e PRECISION_LAND_MODE) Bitmask() string

Bitmask return string representetion of intersects PRECISION_LAND_MODE enums

func (PRECISION_LAND_MODE) MarshalBinary

func (e PRECISION_LAND_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (PRECISION_LAND_MODE) String

func (e PRECISION_LAND_MODE) String() string

func (*PRECISION_LAND_MODE) UnmarshalBinary

func (e *PRECISION_LAND_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type ParamAckTransaction

type ParamAckTransaction struct {
	ParamValue      float32        `json:"ParamValue" `       // Parameter value (new value if PARAM_ACCEPTED, current value otherwise)
	TargetSystem    uint8          `json:"TargetSystem" `     // Id of system that sent PARAM_SET message.
	TargetComponent uint8          `json:"TargetComponent" `  // Id of system that sent PARAM_SET message.
	ParamID         string         `json:"ParamID" len:"16" ` // Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
	ParamType       MAV_PARAM_TYPE `json:"ParamType" `        // Parameter type.
	ParamResult     PARAM_ACK      `json:"ParamResult" `      // Result code.
}

ParamAckTransaction struct (generated typeinfo) Response from a PARAM_SET message when it is used in a transaction.

func (*ParamAckTransaction) Dict

func (m *ParamAckTransaction) Dict() map[string]interface{}

ToMap (generated function)

func (*ParamAckTransaction) Marshal

func (m *ParamAckTransaction) Marshal() ([]byte, error)

Marshal (generated function)

func (ParamAckTransaction) MarshalEasyJSON added in v1.5.0

func (v ParamAckTransaction) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ParamAckTransaction) MarshalJSON added in v1.5.0

func (v ParamAckTransaction) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ParamAckTransaction) MsgID

MsgID (generated function)

func (*ParamAckTransaction) String

func (m *ParamAckTransaction) String() string

String (generated function)

func (*ParamAckTransaction) Unmarshal

func (m *ParamAckTransaction) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ParamAckTransaction) UnmarshalEasyJSON added in v1.5.0

func (v *ParamAckTransaction) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ParamAckTransaction) UnmarshalJSON added in v1.5.0

func (v *ParamAckTransaction) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ParamMapRc

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

ParamMapRc struct (generated typeinfo) Bind a RC channel to a parameter. The parameter should change according to the RC channel value.

func (*ParamMapRc) Dict

func (m *ParamMapRc) Dict() map[string]interface{}

ToMap (generated function)

func (*ParamMapRc) Marshal

func (m *ParamMapRc) Marshal() ([]byte, error)

Marshal (generated function)

func (ParamMapRc) MarshalEasyJSON added in v1.5.0

func (v ParamMapRc) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ParamMapRc) MarshalJSON added in v1.5.0

func (v ParamMapRc) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ParamMapRc) MsgID

func (m *ParamMapRc) MsgID() message.MessageID

MsgID (generated function)

func (*ParamMapRc) String

func (m *ParamMapRc) String() string

String (generated function)

func (*ParamMapRc) Unmarshal

func (m *ParamMapRc) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ParamMapRc) UnmarshalEasyJSON added in v1.5.0

func (v *ParamMapRc) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ParamMapRc) UnmarshalJSON added in v1.5.0

func (v *ParamMapRc) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ParamRequestList

type ParamRequestList struct {
	TargetSystem    uint8 `json:"TargetSystem" `    // System ID
	TargetComponent uint8 `json:"TargetComponent" ` // Component ID
}

ParamRequestList struct (generated typeinfo) Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html

func (*ParamRequestList) Dict

func (m *ParamRequestList) Dict() map[string]interface{}

ToMap (generated function)

func (*ParamRequestList) Marshal

func (m *ParamRequestList) Marshal() ([]byte, error)

Marshal (generated function)

func (ParamRequestList) MarshalEasyJSON added in v1.5.0

func (v ParamRequestList) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ParamRequestList) MarshalJSON added in v1.5.0

func (v ParamRequestList) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ParamRequestList) MsgID

func (m *ParamRequestList) MsgID() message.MessageID

MsgID (generated function)

func (*ParamRequestList) String

func (m *ParamRequestList) String() string

String (generated function)

func (*ParamRequestList) Unmarshal

func (m *ParamRequestList) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ParamRequestList) UnmarshalEasyJSON added in v1.5.0

func (v *ParamRequestList) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ParamRequestList) UnmarshalJSON added in v1.5.0

func (v *ParamRequestList) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ParamRequestRead

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

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

func (*ParamRequestRead) Dict

func (m *ParamRequestRead) Dict() map[string]interface{}

ToMap (generated function)

func (*ParamRequestRead) Marshal

func (m *ParamRequestRead) Marshal() ([]byte, error)

Marshal (generated function)

func (ParamRequestRead) MarshalEasyJSON added in v1.5.0

func (v ParamRequestRead) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ParamRequestRead) MarshalJSON added in v1.5.0

func (v ParamRequestRead) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ParamRequestRead) MsgID

func (m *ParamRequestRead) MsgID() message.MessageID

MsgID (generated function)

func (*ParamRequestRead) String

func (m *ParamRequestRead) String() string

String (generated function)

func (*ParamRequestRead) Unmarshal

func (m *ParamRequestRead) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ParamRequestRead) UnmarshalEasyJSON added in v1.5.0

func (v *ParamRequestRead) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ParamRequestRead) UnmarshalJSON added in v1.5.0

func (v *ParamRequestRead) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ParamSet

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

ParamSet struct (generated typeinfo) Set a parameter value (write new value to permanent storage).

The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html.
PARAM_SET may also be called within the context of a transaction (started with MAV_CMD_PARAM_TRANSACTION). Within a transaction the receiving component should respond with PARAM_ACK_TRANSACTION to the setter component (instead of broadcasting PARAM_VALUE), and PARAM_SET should be re-sent if this is ACK not received.

func (*ParamSet) Dict

func (m *ParamSet) Dict() map[string]interface{}

ToMap (generated function)

func (*ParamSet) Marshal

func (m *ParamSet) Marshal() ([]byte, error)

Marshal (generated function)

func (ParamSet) MarshalEasyJSON added in v1.5.0

func (v ParamSet) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ParamSet) MarshalJSON added in v1.5.0

func (v ParamSet) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ParamSet) MsgID

func (m *ParamSet) MsgID() message.MessageID

MsgID (generated function)

func (*ParamSet) String

func (m *ParamSet) String() string

String (generated function)

func (*ParamSet) Unmarshal

func (m *ParamSet) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ParamSet) UnmarshalEasyJSON added in v1.5.0

func (v *ParamSet) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ParamSet) UnmarshalJSON added in v1.5.0

func (v *ParamSet) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ParamValue

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

ParamValue struct (generated typeinfo) Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html

func (*ParamValue) Dict

func (m *ParamValue) Dict() map[string]interface{}

ToMap (generated function)

func (*ParamValue) Marshal

func (m *ParamValue) Marshal() ([]byte, error)

Marshal (generated function)

func (ParamValue) MarshalEasyJSON added in v1.5.0

func (v ParamValue) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ParamValue) MarshalJSON added in v1.5.0

func (v ParamValue) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ParamValue) MsgID

func (m *ParamValue) MsgID() message.MessageID

MsgID (generated function)

func (*ParamValue) String

func (m *ParamValue) String() string

String (generated function)

func (*ParamValue) Unmarshal

func (m *ParamValue) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ParamValue) UnmarshalEasyJSON added in v1.5.0

func (v *ParamValue) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ParamValue) UnmarshalJSON added in v1.5.0

func (v *ParamValue) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type PidTuning

type PidTuning struct {
	Desired  float32         `json:"Desired" `  // Desired rate.
	Achieved float32         `json:"Achieved" ` // Achieved rate.
	Ff       float32         `json:"Ff" `       // FF component.
	P        float32         `json:"P" `        // P component.
	I        float32         `json:"I" `        // I component.
	D        float32         `json:"D" `        // D component.
	Axis     PID_TUNING_AXIS `json:"Axis" `     // Axis.
}

PidTuning struct (generated typeinfo) PID tuning information.

func (*PidTuning) Dict

func (m *PidTuning) Dict() map[string]interface{}

ToMap (generated function)

func (*PidTuning) Marshal

func (m *PidTuning) Marshal() ([]byte, error)

Marshal (generated function)

func (PidTuning) MarshalEasyJSON added in v1.5.0

func (v PidTuning) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (PidTuning) MarshalJSON added in v1.5.0

func (v PidTuning) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*PidTuning) MsgID

func (m *PidTuning) MsgID() message.MessageID

MsgID (generated function)

func (*PidTuning) String

func (m *PidTuning) String() string

String (generated function)

func (*PidTuning) Unmarshal

func (m *PidTuning) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*PidTuning) UnmarshalEasyJSON added in v1.5.0

func (v *PidTuning) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*PidTuning) UnmarshalJSON added in v1.5.0

func (v *PidTuning) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Ping

type Ping struct {
	TimeUsec        uint64 `json:"TimeUsec" `        // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Seq             uint32 `json:"Seq" `             // PING sequence
	TargetSystem    uint8  `json:"TargetSystem" `    // 0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system
	TargetComponent uint8  `json:"TargetComponent" ` // 0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component.
}

Ping struct (generated typeinfo) A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. The ping microservice is documented at https://mavlink.io/en/services/ping.html

func (*Ping) Dict

func (m *Ping) Dict() map[string]interface{}

ToMap (generated function)

func (*Ping) Marshal

func (m *Ping) Marshal() ([]byte, error)

Marshal (generated function)

func (Ping) MarshalEasyJSON added in v1.5.0

func (v Ping) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Ping) MarshalJSON added in v1.5.0

func (v Ping) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Ping) MsgID

func (m *Ping) MsgID() message.MessageID

MsgID (generated function)

func (*Ping) String

func (m *Ping) String() string

String (generated function)

func (*Ping) Unmarshal

func (m *Ping) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Ping) UnmarshalEasyJSON added in v1.5.0

func (v *Ping) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Ping) UnmarshalJSON added in v1.5.0

func (v *Ping) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type PositionTargetGlobalInt

type PositionTargetGlobalInt struct {
	TimeBootMs      uint32                   `json:"TimeBootMs" `      // [ ms ] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
	LatInt          int32                    `json:"LatInt" `          // [ degE7 ] X Position in WGS84 frame
	LonInt          int32                    `json:"LonInt" `          // [ degE7 ] Y Position in WGS84 frame
	Alt             float32                  `json:"Alt" `             // [ m ] Altitude (MSL, AGL or relative to home altitude, depending on frame)
	Vx              float32                  `json:"Vx" `              // [ m/s ] X velocity in NED frame
	Vy              float32                  `json:"Vy" `              // [ m/s ] Y velocity in NED frame
	Vz              float32                  `json:"Vz" `              // [ m/s ] Z velocity in NED frame
	Afx             float32                  `json:"Afx" `             // [ m/s/s ] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afy             float32                  `json:"Afy" `             // [ m/s/s ] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afz             float32                  `json:"Afz" `             // [ m/s/s ] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Yaw             float32                  `json:"Yaw" `             // [ rad ] yaw setpoint
	YawRate         float32                  `json:"YawRate" `         // [ rad/s ] yaw rate setpoint
	TypeMask        POSITION_TARGET_TYPEMASK `json:"TypeMask" `        // Bitmap to indicate which dimensions should be ignored by the vehicle.
	CoordinateFrame MAV_FRAME                `json:"CoordinateFrame" ` // Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
}

PositionTargetGlobalInt struct (generated typeinfo) Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way.

func (*PositionTargetGlobalInt) Dict

func (m *PositionTargetGlobalInt) Dict() map[string]interface{}

ToMap (generated function)

func (*PositionTargetGlobalInt) Marshal

func (m *PositionTargetGlobalInt) Marshal() ([]byte, error)

Marshal (generated function)

func (PositionTargetGlobalInt) MarshalEasyJSON added in v1.5.0

func (v PositionTargetGlobalInt) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (PositionTargetGlobalInt) MarshalJSON added in v1.5.0

func (v PositionTargetGlobalInt) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*PositionTargetGlobalInt) MsgID

MsgID (generated function)

func (*PositionTargetGlobalInt) String

func (m *PositionTargetGlobalInt) String() string

String (generated function)

func (*PositionTargetGlobalInt) Unmarshal

func (m *PositionTargetGlobalInt) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*PositionTargetGlobalInt) UnmarshalEasyJSON added in v1.5.0

func (v *PositionTargetGlobalInt) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*PositionTargetGlobalInt) UnmarshalJSON added in v1.5.0

func (v *PositionTargetGlobalInt) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type PositionTargetLocalNed

type PositionTargetLocalNed struct {
	TimeBootMs      uint32                   `json:"TimeBootMs" `      // [ ms ] Timestamp (time since system boot).
	X               float32                  `json:"X" `               // [ m ] X Position in NED frame
	Y               float32                  `json:"Y" `               // [ m ] Y Position in NED frame
	Z               float32                  `json:"Z" `               // [ m ] Z Position in NED frame (note, altitude is negative in NED)
	Vx              float32                  `json:"Vx" `              // [ m/s ] X velocity in NED frame
	Vy              float32                  `json:"Vy" `              // [ m/s ] Y velocity in NED frame
	Vz              float32                  `json:"Vz" `              // [ m/s ] Z velocity in NED frame
	Afx             float32                  `json:"Afx" `             // [ m/s/s ] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afy             float32                  `json:"Afy" `             // [ m/s/s ] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afz             float32                  `json:"Afz" `             // [ m/s/s ] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Yaw             float32                  `json:"Yaw" `             // [ rad ] yaw setpoint
	YawRate         float32                  `json:"YawRate" `         // [ rad/s ] yaw rate setpoint
	TypeMask        POSITION_TARGET_TYPEMASK `json:"TypeMask" `        // Bitmap to indicate which dimensions should be ignored by the vehicle.
	CoordinateFrame MAV_FRAME                `json:"CoordinateFrame" ` // Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
}

PositionTargetLocalNed struct (generated typeinfo) Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way.

func (*PositionTargetLocalNed) Dict

func (m *PositionTargetLocalNed) Dict() map[string]interface{}

ToMap (generated function)

func (*PositionTargetLocalNed) Marshal

func (m *PositionTargetLocalNed) Marshal() ([]byte, error)

Marshal (generated function)

func (PositionTargetLocalNed) MarshalEasyJSON added in v1.5.0

func (v PositionTargetLocalNed) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (PositionTargetLocalNed) MarshalJSON added in v1.5.0

func (v PositionTargetLocalNed) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*PositionTargetLocalNed) MsgID

MsgID (generated function)

func (*PositionTargetLocalNed) String

func (m *PositionTargetLocalNed) String() string

String (generated function)

func (*PositionTargetLocalNed) Unmarshal

func (m *PositionTargetLocalNed) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*PositionTargetLocalNed) UnmarshalEasyJSON added in v1.5.0

func (v *PositionTargetLocalNed) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*PositionTargetLocalNed) UnmarshalJSON added in v1.5.0

func (v *PositionTargetLocalNed) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type PowerStatus

type PowerStatus struct {
	Vcc    uint16           `json:"Vcc" `    // [ mV ] 5V rail voltage.
	Vservo uint16           `json:"Vservo" ` // [ mV ] Servo rail voltage.
	Flags  MAV_POWER_STATUS `json:"Flags" `  // Bitmap of power supply status flags.
}

PowerStatus struct (generated typeinfo) Power supply status

func (*PowerStatus) Dict

func (m *PowerStatus) Dict() map[string]interface{}

ToMap (generated function)

func (*PowerStatus) Marshal

func (m *PowerStatus) Marshal() ([]byte, error)

Marshal (generated function)

func (PowerStatus) MarshalEasyJSON added in v1.5.0

func (v PowerStatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (PowerStatus) MarshalJSON added in v1.5.0

func (v PowerStatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*PowerStatus) MsgID

func (m *PowerStatus) MsgID() message.MessageID

MsgID (generated function)

func (*PowerStatus) String

func (m *PowerStatus) String() string

String (generated function)

func (*PowerStatus) Unmarshal

func (m *PowerStatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*PowerStatus) UnmarshalEasyJSON added in v1.5.0

func (v *PowerStatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*PowerStatus) UnmarshalJSON added in v1.5.0

func (v *PowerStatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type RALLY_FLAGS

type RALLY_FLAGS int

RALLY_FLAGS type. Flags in RALLY_POINT message.

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

func (RALLY_FLAGS) Bitmask

func (e RALLY_FLAGS) Bitmask() string

Bitmask return string representetion of intersects RALLY_FLAGS enums

func (RALLY_FLAGS) MarshalBinary

func (e RALLY_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (RALLY_FLAGS) String

func (e RALLY_FLAGS) String() string

func (*RALLY_FLAGS) UnmarshalBinary

func (e *RALLY_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type RC_TYPE

type RC_TYPE int

RC_TYPE type. RC type

const (
	// RC_TYPE_SPEKTRUM_DSM2 enum. Spektrum DSM2
	RC_TYPE_SPEKTRUM_DSM2 RC_TYPE = 0
	// RC_TYPE_SPEKTRUM_DSMX enum. Spektrum DSMX
	RC_TYPE_SPEKTRUM_DSMX RC_TYPE = 1
)

func (RC_TYPE) Bitmask

func (e RC_TYPE) Bitmask() string

Bitmask return string representetion of intersects RC_TYPE enums

func (RC_TYPE) MarshalBinary

func (e RC_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (RC_TYPE) String

func (e RC_TYPE) String() string

func (*RC_TYPE) UnmarshalBinary

func (e *RC_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type ROVER_MODE

type ROVER_MODE int

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

const (
	// ROVER_MODE_MANUAL enum
	ROVER_MODE_MANUAL ROVER_MODE = 0
	// ROVER_MODE_ACRO enum
	ROVER_MODE_ACRO ROVER_MODE = 1
	// ROVER_MODE_STEERING enum
	ROVER_MODE_STEERING ROVER_MODE = 3
	// ROVER_MODE_HOLD enum
	ROVER_MODE_HOLD ROVER_MODE = 4
	// ROVER_MODE_LOITER enum
	ROVER_MODE_LOITER ROVER_MODE = 5
	// ROVER_MODE_FOLLOW enum
	ROVER_MODE_FOLLOW ROVER_MODE = 6
	// ROVER_MODE_SIMPLE enum
	ROVER_MODE_SIMPLE ROVER_MODE = 7
	// ROVER_MODE_AUTO enum
	ROVER_MODE_AUTO ROVER_MODE = 10
	// ROVER_MODE_RTL enum
	ROVER_MODE_RTL ROVER_MODE = 11
	// ROVER_MODE_SMART_RTL enum
	ROVER_MODE_SMART_RTL ROVER_MODE = 12
	// ROVER_MODE_GUIDED enum
	ROVER_MODE_GUIDED ROVER_MODE = 15
	// ROVER_MODE_INITIALIZING enum
	ROVER_MODE_INITIALIZING ROVER_MODE = 16
)

func (ROVER_MODE) Bitmask

func (e ROVER_MODE) Bitmask() string

Bitmask return string representetion of intersects ROVER_MODE enums

func (ROVER_MODE) MarshalBinary

func (e ROVER_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (ROVER_MODE) String

func (e ROVER_MODE) String() string

func (*ROVER_MODE) UnmarshalBinary

func (e *ROVER_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type RTK_BASELINE_COORDINATE_SYSTEM

type RTK_BASELINE_COORDINATE_SYSTEM int

RTK_BASELINE_COORDINATE_SYSTEM type. RTK GPS baseline coordinate system, used for RTK corrections

const (
	// RTK_BASELINE_COORDINATE_SYSTEM_ECEF enum. Earth-centered, Earth-fixed
	RTK_BASELINE_COORDINATE_SYSTEM_ECEF RTK_BASELINE_COORDINATE_SYSTEM = 0
	// RTK_BASELINE_COORDINATE_SYSTEM_NED enum. RTK basestation centered, north, east, down
	RTK_BASELINE_COORDINATE_SYSTEM_NED RTK_BASELINE_COORDINATE_SYSTEM = 1
)

func (RTK_BASELINE_COORDINATE_SYSTEM) Bitmask

Bitmask return string representetion of intersects RTK_BASELINE_COORDINATE_SYSTEM enums

func (RTK_BASELINE_COORDINATE_SYSTEM) MarshalBinary

func (e RTK_BASELINE_COORDINATE_SYSTEM) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (RTK_BASELINE_COORDINATE_SYSTEM) String

func (*RTK_BASELINE_COORDINATE_SYSTEM) UnmarshalBinary

func (e *RTK_BASELINE_COORDINATE_SYSTEM) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type Radio

type Radio struct {
	Rxerrors uint16 `json:"Rxerrors" ` // Receive errors.
	Fixed    uint16 `json:"Fixed" `    // Count of error corrected packets.
	Rssi     uint8  `json:"Rssi" `     // Local signal strength.
	Remrssi  uint8  `json:"Remrssi" `  // Remote signal strength.
	Txbuf    uint8  `json:"Txbuf" `    // [ % ] How full the tx buffer is.
	Noise    uint8  `json:"Noise" `    // Background noise level.
	Remnoise uint8  `json:"Remnoise" ` // Remote background noise level.
}

Radio struct (generated typeinfo) Status generated by radio.

func (*Radio) Dict

func (m *Radio) Dict() map[string]interface{}

ToMap (generated function)

func (*Radio) Marshal

func (m *Radio) Marshal() ([]byte, error)

Marshal (generated function)

func (Radio) MarshalEasyJSON added in v1.5.0

func (v Radio) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Radio) MarshalJSON added in v1.5.0

func (v Radio) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Radio) MsgID

func (m *Radio) MsgID() message.MessageID

MsgID (generated function)

func (*Radio) String

func (m *Radio) String() string

String (generated function)

func (*Radio) Unmarshal

func (m *Radio) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Radio) UnmarshalEasyJSON added in v1.5.0

func (v *Radio) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Radio) UnmarshalJSON added in v1.5.0

func (v *Radio) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type RadioCalibration

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

RadioCalibration struct (generated typeinfo) Complete set of calibration parameters for the radio

func (*RadioCalibration) Dict

func (m *RadioCalibration) Dict() map[string]interface{}

ToMap (generated function)

func (*RadioCalibration) Marshal

func (m *RadioCalibration) Marshal() ([]byte, error)

Marshal (generated function)

func (RadioCalibration) MarshalEasyJSON added in v1.5.0

func (v RadioCalibration) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (RadioCalibration) MarshalJSON added in v1.5.0

func (v RadioCalibration) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*RadioCalibration) MsgID

func (m *RadioCalibration) MsgID() message.MessageID

MsgID (generated function)

func (*RadioCalibration) String

func (m *RadioCalibration) String() string

String (generated function)

func (*RadioCalibration) Unmarshal

func (m *RadioCalibration) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*RadioCalibration) UnmarshalEasyJSON added in v1.5.0

func (v *RadioCalibration) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*RadioCalibration) UnmarshalJSON added in v1.5.0

func (v *RadioCalibration) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type RadioStatus

type RadioStatus struct {
	Rxerrors uint16 `json:"Rxerrors" ` // Count of radio packet receive errors (since boot).
	Fixed    uint16 `json:"Fixed" `    // Count of error corrected radio packets (since boot).
	Rssi     uint8  `json:"Rssi" `     // Local (message sender) recieved signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.
	Remrssi  uint8  `json:"Remrssi" `  // Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.
	Txbuf    uint8  `json:"Txbuf" `    // [ % ] Remaining free transmitter buffer space.
	Noise    uint8  `json:"Noise" `    // Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown.
	Remnoise uint8  `json:"Remnoise" ` // Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], 255: invalid/unknown.
}

RadioStatus struct (generated typeinfo) Status generated by radio and injected into MAVLink stream.

func (*RadioStatus) Dict

func (m *RadioStatus) Dict() map[string]interface{}

ToMap (generated function)

func (*RadioStatus) Marshal

func (m *RadioStatus) Marshal() ([]byte, error)

Marshal (generated function)

func (RadioStatus) MarshalEasyJSON added in v1.5.0

func (v RadioStatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (RadioStatus) MarshalJSON added in v1.5.0

func (v RadioStatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*RadioStatus) MsgID

func (m *RadioStatus) MsgID() message.MessageID

MsgID (generated function)

func (*RadioStatus) String

func (m *RadioStatus) String() string

String (generated function)

func (*RadioStatus) Unmarshal

func (m *RadioStatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*RadioStatus) UnmarshalEasyJSON added in v1.5.0

func (v *RadioStatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*RadioStatus) UnmarshalJSON added in v1.5.0

func (v *RadioStatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type RallyFetchPoint

type RallyFetchPoint struct {
	TargetSystem    uint8 `json:"TargetSystem" `    // System ID.
	TargetComponent uint8 `json:"TargetComponent" ` // Component ID.
	Idx             uint8 `json:"Idx" `             // Point index (first point is 0).
}

RallyFetchPoint struct (generated typeinfo) Request a current rally point from MAV. MAV should respond with a RALLY_POINT message. MAV should not respond if the request is invalid.

func (*RallyFetchPoint) Dict

func (m *RallyFetchPoint) Dict() map[string]interface{}

ToMap (generated function)

func (*RallyFetchPoint) Marshal

func (m *RallyFetchPoint) Marshal() ([]byte, error)

Marshal (generated function)

func (RallyFetchPoint) MarshalEasyJSON added in v1.5.0

func (v RallyFetchPoint) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (RallyFetchPoint) MarshalJSON added in v1.5.0

func (v RallyFetchPoint) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*RallyFetchPoint) MsgID

func (m *RallyFetchPoint) MsgID() message.MessageID

MsgID (generated function)

func (*RallyFetchPoint) String

func (m *RallyFetchPoint) String() string

String (generated function)

func (*RallyFetchPoint) Unmarshal

func (m *RallyFetchPoint) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*RallyFetchPoint) UnmarshalEasyJSON added in v1.5.0

func (v *RallyFetchPoint) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*RallyFetchPoint) UnmarshalJSON added in v1.5.0

func (v *RallyFetchPoint) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type RallyPoint

type RallyPoint struct {
	Lat             int32       `json:"Lat" `             // [ degE7 ] Latitude of point.
	Lng             int32       `json:"Lng" `             // [ degE7 ] Longitude of point.
	Alt             int16       `json:"Alt" `             // [ m ] Transit / loiter altitude relative to home.
	BreakAlt        int16       `json:"BreakAlt" `        // [ m ] Break altitude relative to home.
	LandDir         uint16      `json:"LandDir" `         // [ cdeg ] Heading to aim for when landing.
	TargetSystem    uint8       `json:"TargetSystem" `    // System ID.
	TargetComponent uint8       `json:"TargetComponent" ` // Component ID.
	Idx             uint8       `json:"Idx" `             // Point index (first point is 0).
	Count           uint8       `json:"Count" `           // Total number of points (for sanity checking).
	Flags           RALLY_FLAGS `json:"Flags" `           // Configuration flags.
}

RallyPoint struct (generated typeinfo) A rally point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS.

func (*RallyPoint) Dict

func (m *RallyPoint) Dict() map[string]interface{}

ToMap (generated function)

func (*RallyPoint) Marshal

func (m *RallyPoint) Marshal() ([]byte, error)

Marshal (generated function)

func (RallyPoint) MarshalEasyJSON added in v1.5.0

func (v RallyPoint) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (RallyPoint) MarshalJSON added in v1.5.0

func (v RallyPoint) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*RallyPoint) MsgID

func (m *RallyPoint) MsgID() message.MessageID

MsgID (generated function)

func (*RallyPoint) String

func (m *RallyPoint) String() string

String (generated function)

func (*RallyPoint) Unmarshal

func (m *RallyPoint) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*RallyPoint) UnmarshalEasyJSON added in v1.5.0

func (v *RallyPoint) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*RallyPoint) UnmarshalJSON added in v1.5.0

func (v *RallyPoint) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Rangefinder

type Rangefinder struct {
	Distance float32 `json:"Distance" ` // [ m ] Distance.
	Voltage  float32 `json:"Voltage" `  // [ V ] Raw voltage if available, zero otherwise.
}

Rangefinder struct (generated typeinfo) Rangefinder reporting.

func (*Rangefinder) Dict

func (m *Rangefinder) Dict() map[string]interface{}

ToMap (generated function)

func (*Rangefinder) Marshal

func (m *Rangefinder) Marshal() ([]byte, error)

Marshal (generated function)

func (Rangefinder) MarshalEasyJSON added in v1.5.0

func (v Rangefinder) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Rangefinder) MarshalJSON added in v1.5.0

func (v Rangefinder) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Rangefinder) MsgID

func (m *Rangefinder) MsgID() message.MessageID

MsgID (generated function)

func (*Rangefinder) String

func (m *Rangefinder) String() string

String (generated function)

func (*Rangefinder) Unmarshal

func (m *Rangefinder) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Rangefinder) UnmarshalEasyJSON added in v1.5.0

func (v *Rangefinder) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Rangefinder) UnmarshalJSON added in v1.5.0

func (v *Rangefinder) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type RawImu

type RawImu struct {
	TimeUsec uint64 `json:"TimeUsec" ` // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Xacc     int16  `json:"Xacc" `     // X acceleration (raw)
	Yacc     int16  `json:"Yacc" `     // Y acceleration (raw)
	Zacc     int16  `json:"Zacc" `     // Z acceleration (raw)
	Xgyro    int16  `json:"Xgyro" `    // Angular speed around X axis (raw)
	Ygyro    int16  `json:"Ygyro" `    // Angular speed around Y axis (raw)
	Zgyro    int16  `json:"Zgyro" `    // Angular speed around Z axis (raw)
	Xmag     int16  `json:"Xmag" `     // X Magnetic field (raw)
	Ymag     int16  `json:"Ymag" `     // Y Magnetic field (raw)
	Zmag     int16  `json:"Zmag" `     // Z Magnetic field (raw)
}

RawImu struct (generated typeinfo) The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging.

func (*RawImu) Dict

func (m *RawImu) Dict() map[string]interface{}

ToMap (generated function)

func (*RawImu) Marshal

func (m *RawImu) Marshal() ([]byte, error)

Marshal (generated function)

func (RawImu) MarshalEasyJSON added in v1.5.0

func (v RawImu) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (RawImu) MarshalJSON added in v1.5.0

func (v RawImu) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*RawImu) MsgID

func (m *RawImu) MsgID() message.MessageID

MsgID (generated function)

func (*RawImu) String

func (m *RawImu) String() string

String (generated function)

func (*RawImu) Unmarshal

func (m *RawImu) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*RawImu) UnmarshalEasyJSON added in v1.5.0

func (v *RawImu) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*RawImu) UnmarshalJSON added in v1.5.0

func (v *RawImu) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type RawPressure

type RawPressure struct {
	TimeUsec    uint64 `json:"TimeUsec" `    // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	PressAbs    int16  `json:"PressAbs" `    // Absolute pressure (raw)
	PressDiff1  int16  `json:"PressDiff1" `  // Differential pressure 1 (raw, 0 if nonexistent)
	PressDiff2  int16  `json:"PressDiff2" `  // Differential pressure 2 (raw, 0 if nonexistent)
	Temperature int16  `json:"Temperature" ` // Raw Temperature measurement (raw)
}

RawPressure struct (generated typeinfo) The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values.

func (*RawPressure) Dict

func (m *RawPressure) Dict() map[string]interface{}

ToMap (generated function)

func (*RawPressure) Marshal

func (m *RawPressure) Marshal() ([]byte, error)

Marshal (generated function)

func (RawPressure) MarshalEasyJSON added in v1.5.0

func (v RawPressure) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (RawPressure) MarshalJSON added in v1.5.0

func (v RawPressure) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*RawPressure) MsgID

func (m *RawPressure) MsgID() message.MessageID

MsgID (generated function)

func (*RawPressure) String

func (m *RawPressure) String() string

String (generated function)

func (*RawPressure) Unmarshal

func (m *RawPressure) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*RawPressure) UnmarshalEasyJSON added in v1.5.0

func (v *RawPressure) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*RawPressure) UnmarshalJSON added in v1.5.0

func (v *RawPressure) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type RcChannels

type RcChannels struct {
	TimeBootMs uint32 `json:"TimeBootMs" ` // [ ms ] Timestamp (time since system boot).
	Chan1Raw   uint16 `json:"Chan1Raw" `   // [ us ] RC channel 1 value.
	Chan2Raw   uint16 `json:"Chan2Raw" `   // [ us ] RC channel 2 value.
	Chan3Raw   uint16 `json:"Chan3Raw" `   // [ us ] RC channel 3 value.
	Chan4Raw   uint16 `json:"Chan4Raw" `   // [ us ] RC channel 4 value.
	Chan5Raw   uint16 `json:"Chan5Raw" `   // [ us ] RC channel 5 value.
	Chan6Raw   uint16 `json:"Chan6Raw" `   // [ us ] RC channel 6 value.
	Chan7Raw   uint16 `json:"Chan7Raw" `   // [ us ] RC channel 7 value.
	Chan8Raw   uint16 `json:"Chan8Raw" `   // [ us ] RC channel 8 value.
	Chan9Raw   uint16 `json:"Chan9Raw" `   // [ us ] RC channel 9 value.
	Chan10Raw  uint16 `json:"Chan10Raw" `  // [ us ] RC channel 10 value.
	Chan11Raw  uint16 `json:"Chan11Raw" `  // [ us ] RC channel 11 value.
	Chan12Raw  uint16 `json:"Chan12Raw" `  // [ us ] RC channel 12 value.
	Chan13Raw  uint16 `json:"Chan13Raw" `  // [ us ] RC channel 13 value.
	Chan14Raw  uint16 `json:"Chan14Raw" `  // [ us ] RC channel 14 value.
	Chan15Raw  uint16 `json:"Chan15Raw" `  // [ us ] RC channel 15 value.
	Chan16Raw  uint16 `json:"Chan16Raw" `  // [ us ] RC channel 16 value.
	Chan17Raw  uint16 `json:"Chan17Raw" `  // [ us ] RC channel 17 value.
	Chan18Raw  uint16 `json:"Chan18Raw" `  // [ us ] RC channel 18 value.
	Chancount  uint8  `json:"Chancount" `  // Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
	Rssi       uint8  `json:"Rssi" `       // Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.
}

RcChannels struct (generated typeinfo) The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification.

func (*RcChannels) Dict

func (m *RcChannels) Dict() map[string]interface{}

ToMap (generated function)

func (*RcChannels) Marshal

func (m *RcChannels) Marshal() ([]byte, error)

Marshal (generated function)

func (RcChannels) MarshalEasyJSON added in v1.5.0

func (v RcChannels) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (RcChannels) MarshalJSON added in v1.5.0

func (v RcChannels) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*RcChannels) MsgID

func (m *RcChannels) MsgID() message.MessageID

MsgID (generated function)

func (*RcChannels) String

func (m *RcChannels) String() string

String (generated function)

func (*RcChannels) Unmarshal

func (m *RcChannels) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*RcChannels) UnmarshalEasyJSON added in v1.5.0

func (v *RcChannels) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*RcChannels) UnmarshalJSON added in v1.5.0

func (v *RcChannels) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type RcChannelsOverride

type RcChannelsOverride struct {
	Chan1Raw        uint16 `json:"Chan1Raw" `        // [ us ] RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.
	Chan2Raw        uint16 `json:"Chan2Raw" `        // [ us ] RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.
	Chan3Raw        uint16 `json:"Chan3Raw" `        // [ us ] RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.
	Chan4Raw        uint16 `json:"Chan4Raw" `        // [ us ] RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.
	Chan5Raw        uint16 `json:"Chan5Raw" `        // [ us ] RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.
	Chan6Raw        uint16 `json:"Chan6Raw" `        // [ us ] RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.
	Chan7Raw        uint16 `json:"Chan7Raw" `        // [ us ] RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.
	Chan8Raw        uint16 `json:"Chan8Raw" `        // [ us ] RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.
	TargetSystem    uint8  `json:"TargetSystem" `    // System ID
	TargetComponent uint8  `json:"TargetComponent" ` // Component ID
}

RcChannelsOverride struct (generated typeinfo) The RAW values of the RC channels sent to the MAV to override info received from the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. Note carefully the semantic differences between the first 8 channels and the subsequent channels

func (*RcChannelsOverride) Dict

func (m *RcChannelsOverride) Dict() map[string]interface{}

ToMap (generated function)

func (*RcChannelsOverride) Marshal

func (m *RcChannelsOverride) Marshal() ([]byte, error)

Marshal (generated function)

func (RcChannelsOverride) MarshalEasyJSON added in v1.5.0

func (v RcChannelsOverride) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (RcChannelsOverride) MarshalJSON added in v1.5.0

func (v RcChannelsOverride) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*RcChannelsOverride) MsgID

MsgID (generated function)

func (*RcChannelsOverride) String

func (m *RcChannelsOverride) String() string

String (generated function)

func (*RcChannelsOverride) Unmarshal

func (m *RcChannelsOverride) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*RcChannelsOverride) UnmarshalEasyJSON added in v1.5.0

func (v *RcChannelsOverride) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*RcChannelsOverride) UnmarshalJSON added in v1.5.0

func (v *RcChannelsOverride) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type RcChannelsRaw

type RcChannelsRaw struct {
	TimeBootMs uint32 `json:"TimeBootMs" ` // [ ms ] Timestamp (time since system boot).
	Chan1Raw   uint16 `json:"Chan1Raw" `   // [ us ] RC channel 1 value.
	Chan2Raw   uint16 `json:"Chan2Raw" `   // [ us ] RC channel 2 value.
	Chan3Raw   uint16 `json:"Chan3Raw" `   // [ us ] RC channel 3 value.
	Chan4Raw   uint16 `json:"Chan4Raw" `   // [ us ] RC channel 4 value.
	Chan5Raw   uint16 `json:"Chan5Raw" `   // [ us ] RC channel 5 value.
	Chan6Raw   uint16 `json:"Chan6Raw" `   // [ us ] RC channel 6 value.
	Chan7Raw   uint16 `json:"Chan7Raw" `   // [ us ] RC channel 7 value.
	Chan8Raw   uint16 `json:"Chan8Raw" `   // [ us ] RC channel 8 value.
	Port       uint8  `json:"Port" `       // Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.
	Rssi       uint8  `json:"Rssi" `       // Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.
}

RcChannelsRaw struct (generated typeinfo) The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification.

func (*RcChannelsRaw) Dict

func (m *RcChannelsRaw) Dict() map[string]interface{}

ToMap (generated function)

func (*RcChannelsRaw) Marshal

func (m *RcChannelsRaw) Marshal() ([]byte, error)

Marshal (generated function)

func (RcChannelsRaw) MarshalEasyJSON added in v1.5.0

func (v RcChannelsRaw) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (RcChannelsRaw) MarshalJSON added in v1.5.0

func (v RcChannelsRaw) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*RcChannelsRaw) MsgID

func (m *RcChannelsRaw) MsgID() message.MessageID

MsgID (generated function)

func (*RcChannelsRaw) String

func (m *RcChannelsRaw) String() string

String (generated function)

func (*RcChannelsRaw) Unmarshal

func (m *RcChannelsRaw) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*RcChannelsRaw) UnmarshalEasyJSON added in v1.5.0

func (v *RcChannelsRaw) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*RcChannelsRaw) UnmarshalJSON added in v1.5.0

func (v *RcChannelsRaw) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type RcChannelsScaled

type RcChannelsScaled struct {
	TimeBootMs  uint32 `json:"TimeBootMs" `  // [ ms ] Timestamp (time since system boot).
	Chan1Scaled int16  `json:"Chan1Scaled" ` // RC channel 1 value scaled.
	Chan2Scaled int16  `json:"Chan2Scaled" ` // RC channel 2 value scaled.
	Chan3Scaled int16  `json:"Chan3Scaled" ` // RC channel 3 value scaled.
	Chan4Scaled int16  `json:"Chan4Scaled" ` // RC channel 4 value scaled.
	Chan5Scaled int16  `json:"Chan5Scaled" ` // RC channel 5 value scaled.
	Chan6Scaled int16  `json:"Chan6Scaled" ` // RC channel 6 value scaled.
	Chan7Scaled int16  `json:"Chan7Scaled" ` // RC channel 7 value scaled.
	Chan8Scaled int16  `json:"Chan8Scaled" ` // RC channel 8 value scaled.
	Port        uint8  `json:"Port" `        // Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.
	Rssi        uint8  `json:"Rssi" `        // Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.
}

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

func (*RcChannelsScaled) Dict

func (m *RcChannelsScaled) Dict() map[string]interface{}

ToMap (generated function)

func (*RcChannelsScaled) Marshal

func (m *RcChannelsScaled) Marshal() ([]byte, error)

Marshal (generated function)

func (RcChannelsScaled) MarshalEasyJSON added in v1.5.0

func (v RcChannelsScaled) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (RcChannelsScaled) MarshalJSON added in v1.5.0

func (v RcChannelsScaled) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*RcChannelsScaled) MsgID

func (m *RcChannelsScaled) MsgID() message.MessageID

MsgID (generated function)

func (*RcChannelsScaled) String

func (m *RcChannelsScaled) String() string

String (generated function)

func (*RcChannelsScaled) Unmarshal

func (m *RcChannelsScaled) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*RcChannelsScaled) UnmarshalEasyJSON added in v1.5.0

func (v *RcChannelsScaled) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*RcChannelsScaled) UnmarshalJSON added in v1.5.0

func (v *RcChannelsScaled) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type RemoteLogBlockStatus

type RemoteLogBlockStatus struct {
	Seqno           uint32                             `json:"Seqno" `           // Log data block sequence number.
	TargetSystem    uint8                              `json:"TargetSystem" `    // System ID.
	TargetComponent uint8                              `json:"TargetComponent" ` // Component ID.
	Status          MAV_REMOTE_LOG_DATA_BLOCK_STATUSES `json:"Status" `          // Log data block status.
}

RemoteLogBlockStatus struct (generated typeinfo) Send Status of each log block that autopilot board might have sent.

func (*RemoteLogBlockStatus) Dict

func (m *RemoteLogBlockStatus) Dict() map[string]interface{}

ToMap (generated function)

func (*RemoteLogBlockStatus) Marshal

func (m *RemoteLogBlockStatus) Marshal() ([]byte, error)

Marshal (generated function)

func (RemoteLogBlockStatus) MarshalEasyJSON added in v1.5.0

func (v RemoteLogBlockStatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (RemoteLogBlockStatus) MarshalJSON added in v1.5.0

func (v RemoteLogBlockStatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*RemoteLogBlockStatus) MsgID

MsgID (generated function)

func (*RemoteLogBlockStatus) String

func (m *RemoteLogBlockStatus) String() string

String (generated function)

func (*RemoteLogBlockStatus) Unmarshal

func (m *RemoteLogBlockStatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*RemoteLogBlockStatus) UnmarshalEasyJSON added in v1.5.0

func (v *RemoteLogBlockStatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*RemoteLogBlockStatus) UnmarshalJSON added in v1.5.0

func (v *RemoteLogBlockStatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type RemoteLogDataBlock

type RemoteLogDataBlock struct {
	Seqno           MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS `json:"Seqno" `           // Log data block sequence number.
	TargetSystem    uint8                              `json:"TargetSystem" `    // System ID.
	TargetComponent uint8                              `json:"TargetComponent" ` // Component ID.
	Data            []uint8                            `json:"Data" len:"200" `  // Log data block.
}

RemoteLogDataBlock struct (generated typeinfo) Send a block of log data to remote location.

func (*RemoteLogDataBlock) Dict

func (m *RemoteLogDataBlock) Dict() map[string]interface{}

ToMap (generated function)

func (*RemoteLogDataBlock) Marshal

func (m *RemoteLogDataBlock) Marshal() ([]byte, error)

Marshal (generated function)

func (RemoteLogDataBlock) MarshalEasyJSON added in v1.5.0

func (v RemoteLogDataBlock) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (RemoteLogDataBlock) MarshalJSON added in v1.5.0

func (v RemoteLogDataBlock) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*RemoteLogDataBlock) MsgID

MsgID (generated function)

func (*RemoteLogDataBlock) String

func (m *RemoteLogDataBlock) String() string

String (generated function)

func (*RemoteLogDataBlock) Unmarshal

func (m *RemoteLogDataBlock) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*RemoteLogDataBlock) UnmarshalEasyJSON added in v1.5.0

func (v *RemoteLogDataBlock) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*RemoteLogDataBlock) UnmarshalJSON added in v1.5.0

func (v *RemoteLogDataBlock) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type RequestDataStream

type RequestDataStream struct {
	ReqMessageRate  uint16 `json:"ReqMessageRate" `  // [ Hz ] The requested message rate
	TargetSystem    uint8  `json:"TargetSystem" `    // The target requested to send the message stream.
	TargetComponent uint8  `json:"TargetComponent" ` // The target requested to send the message stream.
	ReqStreamID     uint8  `json:"ReqStreamID" `     // The ID of the requested data stream
	StartStop       uint8  `json:"StartStop" `       // 1 to start sending, 0 to stop sending.
}

RequestDataStream struct (generated typeinfo) Request a data stream.

func (*RequestDataStream) Dict

func (m *RequestDataStream) Dict() map[string]interface{}

ToMap (generated function)

func (*RequestDataStream) Marshal

func (m *RequestDataStream) Marshal() ([]byte, error)

Marshal (generated function)

func (RequestDataStream) MarshalEasyJSON added in v1.5.0

func (v RequestDataStream) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (RequestDataStream) MarshalJSON added in v1.5.0

func (v RequestDataStream) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*RequestDataStream) MsgID

func (m *RequestDataStream) MsgID() message.MessageID

MsgID (generated function)

func (*RequestDataStream) String

func (m *RequestDataStream) String() string

String (generated function)

func (*RequestDataStream) Unmarshal

func (m *RequestDataStream) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*RequestDataStream) UnmarshalEasyJSON added in v1.5.0

func (v *RequestDataStream) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*RequestDataStream) UnmarshalJSON added in v1.5.0

func (v *RequestDataStream) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ResourceRequest

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

ResourceRequest struct (generated typeinfo) The autopilot is requesting a resource (file, binary, other type of data)

func (*ResourceRequest) Dict

func (m *ResourceRequest) Dict() map[string]interface{}

ToMap (generated function)

func (*ResourceRequest) Marshal

func (m *ResourceRequest) Marshal() ([]byte, error)

Marshal (generated function)

func (ResourceRequest) MarshalEasyJSON added in v1.5.0

func (v ResourceRequest) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ResourceRequest) MarshalJSON added in v1.5.0

func (v ResourceRequest) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ResourceRequest) MsgID

func (m *ResourceRequest) MsgID() message.MessageID

MsgID (generated function)

func (*ResourceRequest) String

func (m *ResourceRequest) String() string

String (generated function)

func (*ResourceRequest) Unmarshal

func (m *ResourceRequest) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ResourceRequest) UnmarshalEasyJSON added in v1.5.0

func (v *ResourceRequest) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ResourceRequest) UnmarshalJSON added in v1.5.0

func (v *ResourceRequest) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Rpm

type Rpm struct {
	Rpm1 float32 `json:"Rpm1" ` // RPM Sensor1.
	Rpm2 float32 `json:"Rpm2" ` // RPM Sensor2.
}

Rpm struct (generated typeinfo) RPM sensor output.

func (*Rpm) Dict

func (m *Rpm) Dict() map[string]interface{}

ToMap (generated function)

func (*Rpm) Marshal

func (m *Rpm) Marshal() ([]byte, error)

Marshal (generated function)

func (Rpm) MarshalEasyJSON added in v1.5.0

func (v Rpm) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Rpm) MarshalJSON added in v1.5.0

func (v Rpm) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Rpm) MsgID

func (m *Rpm) MsgID() message.MessageID

MsgID (generated function)

func (*Rpm) String

func (m *Rpm) String() string

String (generated function)

func (*Rpm) Unmarshal

func (m *Rpm) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Rpm) UnmarshalEasyJSON added in v1.5.0

func (v *Rpm) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Rpm) UnmarshalJSON added in v1.5.0

func (v *Rpm) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type SCRIPTING_CMD

type SCRIPTING_CMD int

SCRIPTING_CMD type

const (
	// SCRIPTING_CMD_REPL_START enum. Start a REPL session
	SCRIPTING_CMD_REPL_START SCRIPTING_CMD = 0
	// SCRIPTING_CMD_REPL_STOP enum. End a REPL session
	SCRIPTING_CMD_REPL_STOP SCRIPTING_CMD = 1
)

func (SCRIPTING_CMD) Bitmask

func (e SCRIPTING_CMD) Bitmask() string

Bitmask return string representetion of intersects SCRIPTING_CMD enums

func (SCRIPTING_CMD) MarshalBinary

func (e SCRIPTING_CMD) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (SCRIPTING_CMD) String

func (e SCRIPTING_CMD) String() string

func (*SCRIPTING_CMD) UnmarshalBinary

func (e *SCRIPTING_CMD) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type SERIAL_CONTROL_DEV

type SERIAL_CONTROL_DEV int

SERIAL_CONTROL_DEV type. SERIAL_CONTROL device types

const (
	// SERIAL_CONTROL_DEV_TELEM1 enum. First telemetry port
	SERIAL_CONTROL_DEV_TELEM1 SERIAL_CONTROL_DEV = 0
	// SERIAL_CONTROL_DEV_TELEM2 enum. Second telemetry port
	SERIAL_CONTROL_DEV_TELEM2 SERIAL_CONTROL_DEV = 1
	// SERIAL_CONTROL_DEV_GPS1 enum. First GPS port
	SERIAL_CONTROL_DEV_GPS1 SERIAL_CONTROL_DEV = 2
	// SERIAL_CONTROL_DEV_GPS2 enum. Second GPS port
	SERIAL_CONTROL_DEV_GPS2 SERIAL_CONTROL_DEV = 3
	// SERIAL_CONTROL_DEV_SHELL enum. system shell
	SERIAL_CONTROL_DEV_SHELL SERIAL_CONTROL_DEV = 10
	// SERIAL_CONTROL_SERIAL0 enum. SERIAL0
	SERIAL_CONTROL_SERIAL0 SERIAL_CONTROL_DEV = 100
	// SERIAL_CONTROL_SERIAL1 enum. SERIAL1
	SERIAL_CONTROL_SERIAL1 SERIAL_CONTROL_DEV = 101
	// SERIAL_CONTROL_SERIAL2 enum. SERIAL2
	SERIAL_CONTROL_SERIAL2 SERIAL_CONTROL_DEV = 102
	// SERIAL_CONTROL_SERIAL3 enum. SERIAL3
	SERIAL_CONTROL_SERIAL3 SERIAL_CONTROL_DEV = 103
	// SERIAL_CONTROL_SERIAL4 enum. SERIAL4
	SERIAL_CONTROL_SERIAL4 SERIAL_CONTROL_DEV = 104
	// SERIAL_CONTROL_SERIAL5 enum. SERIAL5
	SERIAL_CONTROL_SERIAL5 SERIAL_CONTROL_DEV = 105
	// SERIAL_CONTROL_SERIAL6 enum. SERIAL6
	SERIAL_CONTROL_SERIAL6 SERIAL_CONTROL_DEV = 106
	// SERIAL_CONTROL_SERIAL7 enum. SERIAL7
	SERIAL_CONTROL_SERIAL7 SERIAL_CONTROL_DEV = 107
	// SERIAL_CONTROL_SERIAL8 enum. SERIAL8
	SERIAL_CONTROL_SERIAL8 SERIAL_CONTROL_DEV = 108
	// SERIAL_CONTROL_SERIAL9 enum. SERIAL9
	SERIAL_CONTROL_SERIAL9 SERIAL_CONTROL_DEV = 109
)

func (SERIAL_CONTROL_DEV) Bitmask

func (e SERIAL_CONTROL_DEV) Bitmask() string

Bitmask return string representetion of intersects SERIAL_CONTROL_DEV enums

func (SERIAL_CONTROL_DEV) MarshalBinary

func (e SERIAL_CONTROL_DEV) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (SERIAL_CONTROL_DEV) String

func (e SERIAL_CONTROL_DEV) String() string

func (*SERIAL_CONTROL_DEV) UnmarshalBinary

func (e *SERIAL_CONTROL_DEV) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type SERIAL_CONTROL_FLAG

type SERIAL_CONTROL_FLAG int

SERIAL_CONTROL_FLAG type. SERIAL_CONTROL flags (bitmask)

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

func (SERIAL_CONTROL_FLAG) Bitmask

func (e SERIAL_CONTROL_FLAG) Bitmask() string

Bitmask return string representetion of intersects SERIAL_CONTROL_FLAG enums

func (SERIAL_CONTROL_FLAG) MarshalBinary

func (e SERIAL_CONTROL_FLAG) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (SERIAL_CONTROL_FLAG) String

func (e SERIAL_CONTROL_FLAG) String() string

func (*SERIAL_CONTROL_FLAG) UnmarshalBinary

func (e *SERIAL_CONTROL_FLAG) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type SET_FOCUS_TYPE

type SET_FOCUS_TYPE int

SET_FOCUS_TYPE type. Focus types for MAV_CMD_SET_CAMERA_FOCUS

const (
	// FOCUS_TYPE_STEP enum. Focus one step increment (-1 for focusing in, 1 for focusing out towards infinity)
	FOCUS_TYPE_STEP SET_FOCUS_TYPE = 0
	// FOCUS_TYPE_CONTINUOUS enum. Continuous focus up/down until stopped (-1 for focusing in, 1 for focusing out towards infinity, 0 to stop focusing)
	FOCUS_TYPE_CONTINUOUS SET_FOCUS_TYPE = 1
	// FOCUS_TYPE_RANGE enum. Focus value as proportion of full camera focus range (a value between 0.0 and 100.0)
	FOCUS_TYPE_RANGE SET_FOCUS_TYPE = 2
	// FOCUS_TYPE_METERS enum. Focus value in metres. Note that there is no message to get the valid focus range of the camera, so this can type can only be used for cameras where the range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)
	FOCUS_TYPE_METERS SET_FOCUS_TYPE = 3
)

func (SET_FOCUS_TYPE) Bitmask

func (e SET_FOCUS_TYPE) Bitmask() string

Bitmask return string representetion of intersects SET_FOCUS_TYPE enums

func (SET_FOCUS_TYPE) MarshalBinary

func (e SET_FOCUS_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (SET_FOCUS_TYPE) String

func (e SET_FOCUS_TYPE) String() string

func (*SET_FOCUS_TYPE) UnmarshalBinary

func (e *SET_FOCUS_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type SPEED_TYPE

type SPEED_TYPE int

SPEED_TYPE type

const (
	// SPEED_TYPE_AIRSPEED enum
	SPEED_TYPE_AIRSPEED SPEED_TYPE = 0
	// SPEED_TYPE_GROUNDSPEED enum
	SPEED_TYPE_GROUNDSPEED SPEED_TYPE = 1
)

func (SPEED_TYPE) Bitmask

func (e SPEED_TYPE) Bitmask() string

Bitmask return string representetion of intersects SPEED_TYPE enums

func (SPEED_TYPE) MarshalBinary

func (e SPEED_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (SPEED_TYPE) String

func (e SPEED_TYPE) String() string

func (*SPEED_TYPE) UnmarshalBinary

func (e *SPEED_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type STORAGE_STATUS

type STORAGE_STATUS int

STORAGE_STATUS type. Flags to indicate the status of camera storage.

const (
	// STORAGE_STATUS_EMPTY enum. Storage is missing (no microSD card loaded for example.)
	STORAGE_STATUS_EMPTY STORAGE_STATUS = 0
	// STORAGE_STATUS_UNFORMATTED enum. Storage present but unformatted
	STORAGE_STATUS_UNFORMATTED STORAGE_STATUS = 1
	// STORAGE_STATUS_READY enum. Storage present and ready
	STORAGE_STATUS_READY STORAGE_STATUS = 2
	// STORAGE_STATUS_NOT_SUPPORTED enum. Camera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored
	STORAGE_STATUS_NOT_SUPPORTED STORAGE_STATUS = 3
)

func (STORAGE_STATUS) Bitmask

func (e STORAGE_STATUS) Bitmask() string

Bitmask return string representetion of intersects STORAGE_STATUS enums

func (STORAGE_STATUS) MarshalBinary

func (e STORAGE_STATUS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (STORAGE_STATUS) String

func (e STORAGE_STATUS) String() string

func (*STORAGE_STATUS) UnmarshalBinary

func (e *STORAGE_STATUS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type STORAGE_TYPE

type STORAGE_TYPE int

STORAGE_TYPE type. Flags to indicate the type of storage.

const (
	// STORAGE_TYPE_UNKNOWN enum. Storage type is not known
	STORAGE_TYPE_UNKNOWN STORAGE_TYPE = 0
	// STORAGE_TYPE_USB_STICK enum. Storage type is USB device
	STORAGE_TYPE_USB_STICK STORAGE_TYPE = 1
	// STORAGE_TYPE_SD enum. Storage type is SD card
	STORAGE_TYPE_SD STORAGE_TYPE = 2
	// STORAGE_TYPE_MICROSD enum. Storage type is microSD card
	STORAGE_TYPE_MICROSD STORAGE_TYPE = 3
	// STORAGE_TYPE_CF enum. Storage type is CFast
	STORAGE_TYPE_CF STORAGE_TYPE = 4
	// STORAGE_TYPE_CFE enum. Storage type is CFexpress
	STORAGE_TYPE_CFE STORAGE_TYPE = 5
	// STORAGE_TYPE_XQD enum. Storage type is XQD
	STORAGE_TYPE_XQD STORAGE_TYPE = 6
	// STORAGE_TYPE_HD enum. Storage type is HD mass storage type
	STORAGE_TYPE_HD STORAGE_TYPE = 7
	// STORAGE_TYPE_OTHER enum. Storage type is other, not listed type
	STORAGE_TYPE_OTHER STORAGE_TYPE = 254
)

func (STORAGE_TYPE) Bitmask

func (e STORAGE_TYPE) Bitmask() string

Bitmask return string representetion of intersects STORAGE_TYPE enums

func (STORAGE_TYPE) MarshalBinary

func (e STORAGE_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (STORAGE_TYPE) String

func (e STORAGE_TYPE) String() string

func (*STORAGE_TYPE) UnmarshalBinary

func (e *STORAGE_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type SUB_MODE

type SUB_MODE int

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

const (
	// SUB_MODE_STABILIZE enum
	SUB_MODE_STABILIZE SUB_MODE = 0
	// SUB_MODE_ACRO enum
	SUB_MODE_ACRO SUB_MODE = 1
	// SUB_MODE_ALT_HOLD enum
	SUB_MODE_ALT_HOLD SUB_MODE = 2
	// SUB_MODE_AUTO enum
	SUB_MODE_AUTO SUB_MODE = 3
	// SUB_MODE_GUIDED enum
	SUB_MODE_GUIDED SUB_MODE = 4
	// SUB_MODE_CIRCLE enum
	SUB_MODE_CIRCLE SUB_MODE = 7
	// SUB_MODE_SURFACE enum
	SUB_MODE_SURFACE SUB_MODE = 9
	// SUB_MODE_POSHOLD enum
	SUB_MODE_POSHOLD SUB_MODE = 16
	// SUB_MODE_MANUAL enum
	SUB_MODE_MANUAL SUB_MODE = 19
)

func (SUB_MODE) Bitmask

func (e SUB_MODE) Bitmask() string

Bitmask return string representetion of intersects SUB_MODE enums

func (SUB_MODE) MarshalBinary

func (e SUB_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (SUB_MODE) String

func (e SUB_MODE) String() string

func (*SUB_MODE) UnmarshalBinary

func (e *SUB_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type SafetyAllowedArea

type SafetyAllowedArea struct {
	P1x   float32   `json:"P1x" `   // [ m ] x position 1 / Latitude 1
	P1y   float32   `json:"P1y" `   // [ m ] y position 1 / Longitude 1
	P1z   float32   `json:"P1z" `   // [ m ] z position 1 / Altitude 1
	P2x   float32   `json:"P2x" `   // [ m ] x position 2 / Latitude 2
	P2y   float32   `json:"P2y" `   // [ m ] y position 2 / Longitude 2
	P2z   float32   `json:"P2z" `   // [ m ] z position 2 / Altitude 2
	Frame MAV_FRAME `json:"Frame" ` // Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
}

SafetyAllowedArea struct (generated typeinfo) Read out the safety zone the MAV currently assumes.

func (*SafetyAllowedArea) Dict

func (m *SafetyAllowedArea) Dict() map[string]interface{}

ToMap (generated function)

func (*SafetyAllowedArea) Marshal

func (m *SafetyAllowedArea) Marshal() ([]byte, error)

Marshal (generated function)

func (SafetyAllowedArea) MarshalEasyJSON added in v1.5.0

func (v SafetyAllowedArea) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (SafetyAllowedArea) MarshalJSON added in v1.5.0

func (v SafetyAllowedArea) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*SafetyAllowedArea) MsgID

func (m *SafetyAllowedArea) MsgID() message.MessageID

MsgID (generated function)

func (*SafetyAllowedArea) String

func (m *SafetyAllowedArea) String() string

String (generated function)

func (*SafetyAllowedArea) Unmarshal

func (m *SafetyAllowedArea) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*SafetyAllowedArea) UnmarshalEasyJSON added in v1.5.0

func (v *SafetyAllowedArea) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*SafetyAllowedArea) UnmarshalJSON added in v1.5.0

func (v *SafetyAllowedArea) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type SafetySetAllowedArea

type SafetySetAllowedArea struct {
	P1x             float32   `json:"P1x" `             // [ m ] x position 1 / Latitude 1
	P1y             float32   `json:"P1y" `             // [ m ] y position 1 / Longitude 1
	P1z             float32   `json:"P1z" `             // [ m ] z position 1 / Altitude 1
	P2x             float32   `json:"P2x" `             // [ m ] x position 2 / Latitude 2
	P2y             float32   `json:"P2y" `             // [ m ] y position 2 / Longitude 2
	P2z             float32   `json:"P2z" `             // [ m ] z position 2 / Altitude 2
	TargetSystem    uint8     `json:"TargetSystem" `    // System ID
	TargetComponent uint8     `json:"TargetComponent" ` // Component ID
	Frame           MAV_FRAME `json:"Frame" `           // Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
}

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

func (*SafetySetAllowedArea) Dict

func (m *SafetySetAllowedArea) Dict() map[string]interface{}

ToMap (generated function)

func (*SafetySetAllowedArea) Marshal

func (m *SafetySetAllowedArea) Marshal() ([]byte, error)

Marshal (generated function)

func (SafetySetAllowedArea) MarshalEasyJSON added in v1.5.0

func (v SafetySetAllowedArea) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (SafetySetAllowedArea) MarshalJSON added in v1.5.0

func (v SafetySetAllowedArea) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*SafetySetAllowedArea) MsgID

MsgID (generated function)

func (*SafetySetAllowedArea) String

func (m *SafetySetAllowedArea) String() string

String (generated function)

func (*SafetySetAllowedArea) Unmarshal

func (m *SafetySetAllowedArea) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*SafetySetAllowedArea) UnmarshalEasyJSON added in v1.5.0

func (v *SafetySetAllowedArea) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*SafetySetAllowedArea) UnmarshalJSON added in v1.5.0

func (v *SafetySetAllowedArea) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ScaledImu

type ScaledImu struct {
	TimeBootMs uint32 `json:"TimeBootMs" ` // [ ms ] Timestamp (time since system boot).
	Xacc       int16  `json:"Xacc" `       // [ mG ] X acceleration
	Yacc       int16  `json:"Yacc" `       // [ mG ] Y acceleration
	Zacc       int16  `json:"Zacc" `       // [ mG ] Z acceleration
	Xgyro      int16  `json:"Xgyro" `      // [ mrad/s ] Angular speed around X axis
	Ygyro      int16  `json:"Ygyro" `      // [ mrad/s ] Angular speed around Y axis
	Zgyro      int16  `json:"Zgyro" `      // [ mrad/s ] Angular speed around Z axis
	Xmag       int16  `json:"Xmag" `       // [ mgauss ] X Magnetic field
	Ymag       int16  `json:"Ymag" `       // [ mgauss ] Y Magnetic field
	Zmag       int16  `json:"Zmag" `       // [ mgauss ] Z Magnetic field
}

ScaledImu struct (generated typeinfo) The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units

func (*ScaledImu) Dict

func (m *ScaledImu) Dict() map[string]interface{}

ToMap (generated function)

func (*ScaledImu) Marshal

func (m *ScaledImu) Marshal() ([]byte, error)

Marshal (generated function)

func (ScaledImu) MarshalEasyJSON added in v1.5.0

func (v ScaledImu) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ScaledImu) MarshalJSON added in v1.5.0

func (v ScaledImu) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ScaledImu) MsgID

func (m *ScaledImu) MsgID() message.MessageID

MsgID (generated function)

func (*ScaledImu) String

func (m *ScaledImu) String() string

String (generated function)

func (*ScaledImu) Unmarshal

func (m *ScaledImu) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ScaledImu) UnmarshalEasyJSON added in v1.5.0

func (v *ScaledImu) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ScaledImu) UnmarshalJSON added in v1.5.0

func (v *ScaledImu) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ScaledImu2

type ScaledImu2 struct {
	TimeBootMs uint32 `json:"TimeBootMs" ` // [ ms ] Timestamp (time since system boot).
	Xacc       int16  `json:"Xacc" `       // [ mG ] X acceleration
	Yacc       int16  `json:"Yacc" `       // [ mG ] Y acceleration
	Zacc       int16  `json:"Zacc" `       // [ mG ] Z acceleration
	Xgyro      int16  `json:"Xgyro" `      // [ mrad/s ] Angular speed around X axis
	Ygyro      int16  `json:"Ygyro" `      // [ mrad/s ] Angular speed around Y axis
	Zgyro      int16  `json:"Zgyro" `      // [ mrad/s ] Angular speed around Z axis
	Xmag       int16  `json:"Xmag" `       // [ mgauss ] X Magnetic field
	Ymag       int16  `json:"Ymag" `       // [ mgauss ] Y Magnetic field
	Zmag       int16  `json:"Zmag" `       // [ mgauss ] Z Magnetic field
}

ScaledImu2 struct (generated typeinfo) The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units

func (*ScaledImu2) Dict

func (m *ScaledImu2) Dict() map[string]interface{}

ToMap (generated function)

func (*ScaledImu2) Marshal

func (m *ScaledImu2) Marshal() ([]byte, error)

Marshal (generated function)

func (ScaledImu2) MarshalEasyJSON added in v1.5.0

func (v ScaledImu2) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ScaledImu2) MarshalJSON added in v1.5.0

func (v ScaledImu2) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ScaledImu2) MsgID

func (m *ScaledImu2) MsgID() message.MessageID

MsgID (generated function)

func (*ScaledImu2) String

func (m *ScaledImu2) String() string

String (generated function)

func (*ScaledImu2) Unmarshal

func (m *ScaledImu2) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ScaledImu2) UnmarshalEasyJSON added in v1.5.0

func (v *ScaledImu2) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ScaledImu2) UnmarshalJSON added in v1.5.0

func (v *ScaledImu2) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ScaledImu3

type ScaledImu3 struct {
	TimeBootMs uint32 `json:"TimeBootMs" ` // [ ms ] Timestamp (time since system boot).
	Xacc       int16  `json:"Xacc" `       // [ mG ] X acceleration
	Yacc       int16  `json:"Yacc" `       // [ mG ] Y acceleration
	Zacc       int16  `json:"Zacc" `       // [ mG ] Z acceleration
	Xgyro      int16  `json:"Xgyro" `      // [ mrad/s ] Angular speed around X axis
	Ygyro      int16  `json:"Ygyro" `      // [ mrad/s ] Angular speed around Y axis
	Zgyro      int16  `json:"Zgyro" `      // [ mrad/s ] Angular speed around Z axis
	Xmag       int16  `json:"Xmag" `       // [ mgauss ] X Magnetic field
	Ymag       int16  `json:"Ymag" `       // [ mgauss ] Y Magnetic field
	Zmag       int16  `json:"Zmag" `       // [ mgauss ] Z Magnetic field
}

ScaledImu3 struct (generated typeinfo) The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units

func (*ScaledImu3) Dict

func (m *ScaledImu3) Dict() map[string]interface{}

ToMap (generated function)

func (*ScaledImu3) Marshal

func (m *ScaledImu3) Marshal() ([]byte, error)

Marshal (generated function)

func (ScaledImu3) MarshalEasyJSON added in v1.5.0

func (v ScaledImu3) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ScaledImu3) MarshalJSON added in v1.5.0

func (v ScaledImu3) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ScaledImu3) MsgID

func (m *ScaledImu3) MsgID() message.MessageID

MsgID (generated function)

func (*ScaledImu3) String

func (m *ScaledImu3) String() string

String (generated function)

func (*ScaledImu3) Unmarshal

func (m *ScaledImu3) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ScaledImu3) UnmarshalEasyJSON added in v1.5.0

func (v *ScaledImu3) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ScaledImu3) UnmarshalJSON added in v1.5.0

func (v *ScaledImu3) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ScaledPressure

type ScaledPressure struct {
	TimeBootMs  uint32  `json:"TimeBootMs" `  // [ ms ] Timestamp (time since system boot).
	PressAbs    float32 `json:"PressAbs" `    // [ hPa ] Absolute pressure
	PressDiff   float32 `json:"PressDiff" `   // [ hPa ] Differential pressure 1
	Temperature int16   `json:"Temperature" ` // [ cdegC ] Absolute pressure temperature
}

ScaledPressure struct (generated typeinfo) The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.

func (*ScaledPressure) Dict

func (m *ScaledPressure) Dict() map[string]interface{}

ToMap (generated function)

func (*ScaledPressure) Marshal

func (m *ScaledPressure) Marshal() ([]byte, error)

Marshal (generated function)

func (ScaledPressure) MarshalEasyJSON added in v1.5.0

func (v ScaledPressure) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ScaledPressure) MarshalJSON added in v1.5.0

func (v ScaledPressure) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ScaledPressure) MsgID

func (m *ScaledPressure) MsgID() message.MessageID

MsgID (generated function)

func (*ScaledPressure) String

func (m *ScaledPressure) String() string

String (generated function)

func (*ScaledPressure) Unmarshal

func (m *ScaledPressure) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ScaledPressure) UnmarshalEasyJSON added in v1.5.0

func (v *ScaledPressure) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ScaledPressure) UnmarshalJSON added in v1.5.0

func (v *ScaledPressure) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ScaledPressure2

type ScaledPressure2 struct {
	TimeBootMs  uint32  `json:"TimeBootMs" `  // [ ms ] Timestamp (time since system boot).
	PressAbs    float32 `json:"PressAbs" `    // [ hPa ] Absolute pressure
	PressDiff   float32 `json:"PressDiff" `   // [ hPa ] Differential pressure
	Temperature int16   `json:"Temperature" ` // [ cdegC ] Absolute pressure temperature
}

ScaledPressure2 struct (generated typeinfo) Barometer readings for 2nd barometer

func (*ScaledPressure2) Dict

func (m *ScaledPressure2) Dict() map[string]interface{}

ToMap (generated function)

func (*ScaledPressure2) Marshal

func (m *ScaledPressure2) Marshal() ([]byte, error)

Marshal (generated function)

func (ScaledPressure2) MarshalEasyJSON added in v1.5.0

func (v ScaledPressure2) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ScaledPressure2) MarshalJSON added in v1.5.0

func (v ScaledPressure2) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ScaledPressure2) MsgID

func (m *ScaledPressure2) MsgID() message.MessageID

MsgID (generated function)

func (*ScaledPressure2) String

func (m *ScaledPressure2) String() string

String (generated function)

func (*ScaledPressure2) Unmarshal

func (m *ScaledPressure2) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ScaledPressure2) UnmarshalEasyJSON added in v1.5.0

func (v *ScaledPressure2) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ScaledPressure2) UnmarshalJSON added in v1.5.0

func (v *ScaledPressure2) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ScaledPressure3

type ScaledPressure3 struct {
	TimeBootMs  uint32  `json:"TimeBootMs" `  // [ ms ] Timestamp (time since system boot).
	PressAbs    float32 `json:"PressAbs" `    // [ hPa ] Absolute pressure
	PressDiff   float32 `json:"PressDiff" `   // [ hPa ] Differential pressure
	Temperature int16   `json:"Temperature" ` // [ cdegC ] Absolute pressure temperature
}

ScaledPressure3 struct (generated typeinfo) Barometer readings for 3rd barometer

func (*ScaledPressure3) Dict

func (m *ScaledPressure3) Dict() map[string]interface{}

ToMap (generated function)

func (*ScaledPressure3) Marshal

func (m *ScaledPressure3) Marshal() ([]byte, error)

Marshal (generated function)

func (ScaledPressure3) MarshalEasyJSON added in v1.5.0

func (v ScaledPressure3) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ScaledPressure3) MarshalJSON added in v1.5.0

func (v ScaledPressure3) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ScaledPressure3) MsgID

func (m *ScaledPressure3) MsgID() message.MessageID

MsgID (generated function)

func (*ScaledPressure3) String

func (m *ScaledPressure3) String() string

String (generated function)

func (*ScaledPressure3) Unmarshal

func (m *ScaledPressure3) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ScaledPressure3) UnmarshalEasyJSON added in v1.5.0

func (v *ScaledPressure3) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ScaledPressure3) UnmarshalJSON added in v1.5.0

func (v *ScaledPressure3) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type SensorOffsets

type SensorOffsets struct {
	MagDeclination float32 `json:"MagDeclination" ` // [ rad ] Magnetic declination.
	RawPress       int32   `json:"RawPress" `       // Raw pressure from barometer.
	RawTemp        int32   `json:"RawTemp" `        // Raw temperature from barometer.
	GyroCalX       float32 `json:"GyroCalX" `       // Gyro X calibration.
	GyroCalY       float32 `json:"GyroCalY" `       // Gyro Y calibration.
	GyroCalZ       float32 `json:"GyroCalZ" `       // Gyro Z calibration.
	AccelCalX      float32 `json:"AccelCalX" `      // Accel X calibration.
	AccelCalY      float32 `json:"AccelCalY" `      // Accel Y calibration.
	AccelCalZ      float32 `json:"AccelCalZ" `      // Accel Z calibration.
	MagOfsX        int16   `json:"MagOfsX" `        // Magnetometer X offset.
	MagOfsY        int16   `json:"MagOfsY" `        // Magnetometer Y offset.
	MagOfsZ        int16   `json:"MagOfsZ" `        // Magnetometer Z offset.
}

SensorOffsets struct (generated typeinfo) Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process.

func (*SensorOffsets) Dict

func (m *SensorOffsets) Dict() map[string]interface{}

ToMap (generated function)

func (*SensorOffsets) Marshal

func (m *SensorOffsets) Marshal() ([]byte, error)

Marshal (generated function)

func (SensorOffsets) MarshalEasyJSON added in v1.5.0

func (v SensorOffsets) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (SensorOffsets) MarshalJSON added in v1.5.0

func (v SensorOffsets) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*SensorOffsets) MsgID

func (m *SensorOffsets) MsgID() message.MessageID

MsgID (generated function)

func (*SensorOffsets) String

func (m *SensorOffsets) String() string

String (generated function)

func (*SensorOffsets) Unmarshal

func (m *SensorOffsets) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*SensorOffsets) UnmarshalEasyJSON added in v1.5.0

func (v *SensorOffsets) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*SensorOffsets) UnmarshalJSON added in v1.5.0

func (v *SensorOffsets) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type SerialControl

type SerialControl struct {
	Baudrate uint32              `json:"Baudrate" `      // [ bits/s ] Baudrate of transfer. Zero means no change.
	Timeout  uint16              `json:"Timeout" `       // [ ms ] Timeout for reply data
	Device   SERIAL_CONTROL_DEV  `json:"Device" `        // Serial control device type.
	Flags    SERIAL_CONTROL_FLAG `json:"Flags" `         // Bitmap of serial control flags.
	Count    uint8               `json:"Count" `         // [ bytes ] how many bytes in this transfer
	Data     []uint8             `json:"Data" len:"70" ` // serial data
}

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

func (*SerialControl) Dict

func (m *SerialControl) Dict() map[string]interface{}

ToMap (generated function)

func (*SerialControl) Marshal

func (m *SerialControl) Marshal() ([]byte, error)

Marshal (generated function)

func (SerialControl) MarshalEasyJSON added in v1.5.0

func (v SerialControl) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (SerialControl) MarshalJSON added in v1.5.0

func (v SerialControl) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*SerialControl) MsgID

func (m *SerialControl) MsgID() message.MessageID

MsgID (generated function)

func (*SerialControl) String

func (m *SerialControl) String() string

String (generated function)

func (*SerialControl) Unmarshal

func (m *SerialControl) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*SerialControl) UnmarshalEasyJSON added in v1.5.0

func (v *SerialControl) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*SerialControl) UnmarshalJSON added in v1.5.0

func (v *SerialControl) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ServoOutputRaw

type ServoOutputRaw struct {
	TimeUsec  uint32 `json:"TimeUsec" `  // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Servo1Raw uint16 `json:"Servo1Raw" ` // [ us ] Servo output 1 value
	Servo2Raw uint16 `json:"Servo2Raw" ` // [ us ] Servo output 2 value
	Servo3Raw uint16 `json:"Servo3Raw" ` // [ us ] Servo output 3 value
	Servo4Raw uint16 `json:"Servo4Raw" ` // [ us ] Servo output 4 value
	Servo5Raw uint16 `json:"Servo5Raw" ` // [ us ] Servo output 5 value
	Servo6Raw uint16 `json:"Servo6Raw" ` // [ us ] Servo output 6 value
	Servo7Raw uint16 `json:"Servo7Raw" ` // [ us ] Servo output 7 value
	Servo8Raw uint16 `json:"Servo8Raw" ` // [ us ] Servo output 8 value
	Port      uint8  `json:"Port" `      // Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.
}

ServoOutputRaw struct (generated typeinfo) Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%.

func (*ServoOutputRaw) Dict

func (m *ServoOutputRaw) Dict() map[string]interface{}

ToMap (generated function)

func (*ServoOutputRaw) Marshal

func (m *ServoOutputRaw) Marshal() ([]byte, error)

Marshal (generated function)

func (ServoOutputRaw) MarshalEasyJSON added in v1.5.0

func (v ServoOutputRaw) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ServoOutputRaw) MarshalJSON added in v1.5.0

func (v ServoOutputRaw) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ServoOutputRaw) MsgID

func (m *ServoOutputRaw) MsgID() message.MessageID

MsgID (generated function)

func (*ServoOutputRaw) String

func (m *ServoOutputRaw) String() string

String (generated function)

func (*ServoOutputRaw) Unmarshal

func (m *ServoOutputRaw) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ServoOutputRaw) UnmarshalEasyJSON added in v1.5.0

func (v *ServoOutputRaw) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ServoOutputRaw) UnmarshalJSON added in v1.5.0

func (v *ServoOutputRaw) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type SetActuatorControlTarget

type SetActuatorControlTarget struct {
	TimeUsec        uint64    `json:"TimeUsec" `         // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	Controls        []float32 `json:"Controls" len:"8" ` // Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.
	GroupMlx        uint8     `json:"GroupMlx" `         // Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.
	TargetSystem    uint8     `json:"TargetSystem" `     // System ID
	TargetComponent uint8     `json:"TargetComponent" `  // Component ID
}

SetActuatorControlTarget struct (generated typeinfo) Set the vehicle attitude and body angular rates.

func (*SetActuatorControlTarget) Dict

func (m *SetActuatorControlTarget) Dict() map[string]interface{}

ToMap (generated function)

func (*SetActuatorControlTarget) Marshal

func (m *SetActuatorControlTarget) Marshal() ([]byte, error)

Marshal (generated function)

func (SetActuatorControlTarget) MarshalEasyJSON added in v1.5.0

func (v SetActuatorControlTarget) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (SetActuatorControlTarget) MarshalJSON added in v1.5.0

func (v SetActuatorControlTarget) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*SetActuatorControlTarget) MsgID

MsgID (generated function)

func (*SetActuatorControlTarget) String

func (m *SetActuatorControlTarget) String() string

String (generated function)

func (*SetActuatorControlTarget) Unmarshal

func (m *SetActuatorControlTarget) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*SetActuatorControlTarget) UnmarshalEasyJSON added in v1.5.0

func (v *SetActuatorControlTarget) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*SetActuatorControlTarget) UnmarshalJSON added in v1.5.0

func (v *SetActuatorControlTarget) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type SetAttitudeTarget

type SetAttitudeTarget struct {
	TimeBootMs      uint32                   `json:"TimeBootMs" `      // [ ms ] Timestamp (time since system boot).
	Q               []float32                `json:"Q" len:"4" `       // Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
	BodyRollRate    float32                  `json:"BodyRollRate" `    // [ rad/s ] Body roll rate
	BodyPitchRate   float32                  `json:"BodyPitchRate" `   // [ rad/s ] Body pitch rate
	BodyYawRate     float32                  `json:"BodyYawRate" `     // [ rad/s ] Body yaw rate
	Thrust          float32                  `json:"Thrust" `          // Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
	TargetSystem    uint8                    `json:"TargetSystem" `    // System ID
	TargetComponent uint8                    `json:"TargetComponent" ` // Component ID
	TypeMask        ATTITUDE_TARGET_TYPEMASK `json:"TypeMask" `        // Bitmap to indicate which dimensions should be ignored by the vehicle.
}

SetAttitudeTarget struct (generated typeinfo) Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system).

func (*SetAttitudeTarget) Dict

func (m *SetAttitudeTarget) Dict() map[string]interface{}

ToMap (generated function)

func (*SetAttitudeTarget) Marshal

func (m *SetAttitudeTarget) Marshal() ([]byte, error)

Marshal (generated function)

func (SetAttitudeTarget) MarshalEasyJSON added in v1.5.0

func (v SetAttitudeTarget) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (SetAttitudeTarget) MarshalJSON added in v1.5.0

func (v SetAttitudeTarget) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*SetAttitudeTarget) MsgID

func (m *SetAttitudeTarget) MsgID() message.MessageID

MsgID (generated function)

func (*SetAttitudeTarget) String

func (m *SetAttitudeTarget) String() string

String (generated function)

func (*SetAttitudeTarget) Unmarshal

func (m *SetAttitudeTarget) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*SetAttitudeTarget) UnmarshalEasyJSON added in v1.5.0

func (v *SetAttitudeTarget) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*SetAttitudeTarget) UnmarshalJSON added in v1.5.0

func (v *SetAttitudeTarget) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type SetGpsGlobalOrigin

type SetGpsGlobalOrigin struct {
	Latitude     int32 `json:"Latitude" `     // [ degE7 ] Latitude (WGS84)
	Longitude    int32 `json:"Longitude" `    // [ degE7 ] Longitude (WGS84)
	Altitude     int32 `json:"Altitude" `     // [ mm ] Altitude (MSL). Positive for up.
	TargetSystem uint8 `json:"TargetSystem" ` // System ID
}

SetGpsGlobalOrigin struct (generated typeinfo) Sets the GPS co-ordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor.

func (*SetGpsGlobalOrigin) Dict

func (m *SetGpsGlobalOrigin) Dict() map[string]interface{}

ToMap (generated function)

func (*SetGpsGlobalOrigin) Marshal

func (m *SetGpsGlobalOrigin) Marshal() ([]byte, error)

Marshal (generated function)

func (SetGpsGlobalOrigin) MarshalEasyJSON added in v1.5.0

func (v SetGpsGlobalOrigin) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (SetGpsGlobalOrigin) MarshalJSON added in v1.5.0

func (v SetGpsGlobalOrigin) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*SetGpsGlobalOrigin) MsgID

MsgID (generated function)

func (*SetGpsGlobalOrigin) String

func (m *SetGpsGlobalOrigin) String() string

String (generated function)

func (*SetGpsGlobalOrigin) Unmarshal

func (m *SetGpsGlobalOrigin) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*SetGpsGlobalOrigin) UnmarshalEasyJSON added in v1.5.0

func (v *SetGpsGlobalOrigin) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*SetGpsGlobalOrigin) UnmarshalJSON added in v1.5.0

func (v *SetGpsGlobalOrigin) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type SetHomePosition

type SetHomePosition struct {
	Latitude     int32     `json:"Latitude" `     // [ degE7 ] Latitude (WGS84)
	Longitude    int32     `json:"Longitude" `    // [ degE7 ] Longitude (WGS84)
	Altitude     int32     `json:"Altitude" `     // [ mm ] Altitude (MSL). Positive for up.
	X            float32   `json:"X" `            // [ m ] Local X position of this position in the local coordinate frame
	Y            float32   `json:"Y" `            // [ m ] Local Y position of this position in the local coordinate frame
	Z            float32   `json:"Z" `            // [ m ] Local Z position of this position in the local coordinate frame
	Q            []float32 `json:"Q" len:"4" `    // World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
	ApproachX    float32   `json:"ApproachX" `    // [ m ] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
	ApproachY    float32   `json:"ApproachY" `    // [ m ] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
	ApproachZ    float32   `json:"ApproachZ" `    // [ m ] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
	TargetSystem uint8     `json:"TargetSystem" ` // System ID.
}

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

func (*SetHomePosition) Dict

func (m *SetHomePosition) Dict() map[string]interface{}

ToMap (generated function)

func (*SetHomePosition) Marshal

func (m *SetHomePosition) Marshal() ([]byte, error)

Marshal (generated function)

func (SetHomePosition) MarshalEasyJSON added in v1.5.0

func (v SetHomePosition) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (SetHomePosition) MarshalJSON added in v1.5.0

func (v SetHomePosition) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*SetHomePosition) MsgID

func (m *SetHomePosition) MsgID() message.MessageID

MsgID (generated function)

func (*SetHomePosition) String

func (m *SetHomePosition) String() string

String (generated function)

func (*SetHomePosition) Unmarshal

func (m *SetHomePosition) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*SetHomePosition) UnmarshalEasyJSON added in v1.5.0

func (v *SetHomePosition) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*SetHomePosition) UnmarshalJSON added in v1.5.0

func (v *SetHomePosition) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type SetMagOffsets

type SetMagOffsets struct {
	MagOfsX         int16 `json:"MagOfsX" `         // Magnetometer X offset.
	MagOfsY         int16 `json:"MagOfsY" `         // Magnetometer Y offset.
	MagOfsZ         int16 `json:"MagOfsZ" `         // Magnetometer Z offset.
	TargetSystem    uint8 `json:"TargetSystem" `    // System ID.
	TargetComponent uint8 `json:"TargetComponent" ` // Component ID.
}

SetMagOffsets struct (generated typeinfo) Set the magnetometer offsets

func (*SetMagOffsets) Dict

func (m *SetMagOffsets) Dict() map[string]interface{}

ToMap (generated function)

func (*SetMagOffsets) Marshal

func (m *SetMagOffsets) Marshal() ([]byte, error)

Marshal (generated function)

func (SetMagOffsets) MarshalEasyJSON added in v1.5.0

func (v SetMagOffsets) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (SetMagOffsets) MarshalJSON added in v1.5.0

func (v SetMagOffsets) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*SetMagOffsets) MsgID

func (m *SetMagOffsets) MsgID() message.MessageID

MsgID (generated function)

func (*SetMagOffsets) String

func (m *SetMagOffsets) String() string

String (generated function)

func (*SetMagOffsets) Unmarshal

func (m *SetMagOffsets) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*SetMagOffsets) UnmarshalEasyJSON added in v1.5.0

func (v *SetMagOffsets) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*SetMagOffsets) UnmarshalJSON added in v1.5.0

func (v *SetMagOffsets) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type SetMode

type SetMode struct {
	CustomMode   uint32   `json:"CustomMode" `   // The new autopilot-specific mode. This field can be ignored by an autopilot.
	TargetSystem uint8    `json:"TargetSystem" ` // The system setting the mode
	BaseMode     MAV_MODE `json:"BaseMode" `     // The new base mode.
}

SetMode struct (generated typeinfo) Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.

func (*SetMode) Dict

func (m *SetMode) Dict() map[string]interface{}

ToMap (generated function)

func (*SetMode) Marshal

func (m *SetMode) Marshal() ([]byte, error)

Marshal (generated function)

func (SetMode) MarshalEasyJSON added in v1.5.0

func (v SetMode) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (SetMode) MarshalJSON added in v1.5.0

func (v SetMode) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*SetMode) MsgID

func (m *SetMode) MsgID() message.MessageID

MsgID (generated function)

func (*SetMode) String

func (m *SetMode) String() string

String (generated function)

func (*SetMode) Unmarshal

func (m *SetMode) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*SetMode) UnmarshalEasyJSON added in v1.5.0

func (v *SetMode) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*SetMode) UnmarshalJSON added in v1.5.0

func (v *SetMode) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type SetPositionTargetGlobalInt

type SetPositionTargetGlobalInt struct {
	TimeBootMs      uint32                   `json:"TimeBootMs" `      // [ ms ] Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
	LatInt          int32                    `json:"LatInt" `          // [ degE7 ] X Position in WGS84 frame
	LonInt          int32                    `json:"LonInt" `          // [ degE7 ] Y Position in WGS84 frame
	Alt             float32                  `json:"Alt" `             // [ m ] Altitude (MSL, Relative to home, or AGL - depending on frame)
	Vx              float32                  `json:"Vx" `              // [ m/s ] X velocity in NED frame
	Vy              float32                  `json:"Vy" `              // [ m/s ] Y velocity in NED frame
	Vz              float32                  `json:"Vz" `              // [ m/s ] Z velocity in NED frame
	Afx             float32                  `json:"Afx" `             // [ m/s/s ] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afy             float32                  `json:"Afy" `             // [ m/s/s ] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afz             float32                  `json:"Afz" `             // [ m/s/s ] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Yaw             float32                  `json:"Yaw" `             // [ rad ] yaw setpoint
	YawRate         float32                  `json:"YawRate" `         // [ rad/s ] yaw rate setpoint
	TypeMask        POSITION_TARGET_TYPEMASK `json:"TypeMask" `        // Bitmap to indicate which dimensions should be ignored by the vehicle.
	TargetSystem    uint8                    `json:"TargetSystem" `    // System ID
	TargetComponent uint8                    `json:"TargetComponent" ` // Component ID
	CoordinateFrame MAV_FRAME                `json:"CoordinateFrame" ` // Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
}

SetPositionTargetGlobalInt struct (generated typeinfo) Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system).

func (*SetPositionTargetGlobalInt) Dict

func (m *SetPositionTargetGlobalInt) Dict() map[string]interface{}

ToMap (generated function)

func (*SetPositionTargetGlobalInt) Marshal

func (m *SetPositionTargetGlobalInt) Marshal() ([]byte, error)

Marshal (generated function)

func (SetPositionTargetGlobalInt) MarshalEasyJSON added in v1.5.0

func (v SetPositionTargetGlobalInt) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (SetPositionTargetGlobalInt) MarshalJSON added in v1.5.0

func (v SetPositionTargetGlobalInt) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*SetPositionTargetGlobalInt) MsgID

MsgID (generated function)

func (*SetPositionTargetGlobalInt) String

func (m *SetPositionTargetGlobalInt) String() string

String (generated function)

func (*SetPositionTargetGlobalInt) Unmarshal

func (m *SetPositionTargetGlobalInt) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*SetPositionTargetGlobalInt) UnmarshalEasyJSON added in v1.5.0

func (v *SetPositionTargetGlobalInt) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*SetPositionTargetGlobalInt) UnmarshalJSON added in v1.5.0

func (v *SetPositionTargetGlobalInt) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type SetPositionTargetLocalNed

type SetPositionTargetLocalNed struct {
	TimeBootMs      uint32                   `json:"TimeBootMs" `      // [ ms ] Timestamp (time since system boot).
	X               float32                  `json:"X" `               // [ m ] X Position in NED frame
	Y               float32                  `json:"Y" `               // [ m ] Y Position in NED frame
	Z               float32                  `json:"Z" `               // [ m ] Z Position in NED frame (note, altitude is negative in NED)
	Vx              float32                  `json:"Vx" `              // [ m/s ] X velocity in NED frame
	Vy              float32                  `json:"Vy" `              // [ m/s ] Y velocity in NED frame
	Vz              float32                  `json:"Vz" `              // [ m/s ] Z velocity in NED frame
	Afx             float32                  `json:"Afx" `             // [ m/s/s ] X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afy             float32                  `json:"Afy" `             // [ m/s/s ] Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Afz             float32                  `json:"Afz" `             // [ m/s/s ] Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
	Yaw             float32                  `json:"Yaw" `             // [ rad ] yaw setpoint
	YawRate         float32                  `json:"YawRate" `         // [ rad/s ] yaw rate setpoint
	TypeMask        POSITION_TARGET_TYPEMASK `json:"TypeMask" `        // Bitmap to indicate which dimensions should be ignored by the vehicle.
	TargetSystem    uint8                    `json:"TargetSystem" `    // System ID
	TargetComponent uint8                    `json:"TargetComponent" ` // Component ID
	CoordinateFrame MAV_FRAME                `json:"CoordinateFrame" ` // Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
}

SetPositionTargetLocalNed struct (generated typeinfo) Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system).

func (*SetPositionTargetLocalNed) Dict

func (m *SetPositionTargetLocalNed) Dict() map[string]interface{}

ToMap (generated function)

func (*SetPositionTargetLocalNed) Marshal

func (m *SetPositionTargetLocalNed) Marshal() ([]byte, error)

Marshal (generated function)

func (SetPositionTargetLocalNed) MarshalEasyJSON added in v1.5.0

func (v SetPositionTargetLocalNed) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (SetPositionTargetLocalNed) MarshalJSON added in v1.5.0

func (v SetPositionTargetLocalNed) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*SetPositionTargetLocalNed) MsgID

MsgID (generated function)

func (*SetPositionTargetLocalNed) String

func (m *SetPositionTargetLocalNed) String() string

String (generated function)

func (*SetPositionTargetLocalNed) Unmarshal

func (m *SetPositionTargetLocalNed) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*SetPositionTargetLocalNed) UnmarshalEasyJSON added in v1.5.0

func (v *SetPositionTargetLocalNed) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*SetPositionTargetLocalNed) UnmarshalJSON added in v1.5.0

func (v *SetPositionTargetLocalNed) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type SimState

type SimState struct {
	Q1         float32 `json:"Q1" `         // True attitude quaternion component 1, w (1 in null-rotation)
	Q2         float32 `json:"Q2" `         // True attitude quaternion component 2, x (0 in null-rotation)
	Q3         float32 `json:"Q3" `         // True attitude quaternion component 3, y (0 in null-rotation)
	Q4         float32 `json:"Q4" `         // True attitude quaternion component 4, z (0 in null-rotation)
	Roll       float32 `json:"Roll" `       // Attitude roll expressed as Euler angles, not recommended except for human-readable outputs
	Pitch      float32 `json:"Pitch" `      // Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs
	Yaw        float32 `json:"Yaw" `        // Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs
	Xacc       float32 `json:"Xacc" `       // [ m/s/s ] X acceleration
	Yacc       float32 `json:"Yacc" `       // [ m/s/s ] Y acceleration
	Zacc       float32 `json:"Zacc" `       // [ m/s/s ] Z acceleration
	Xgyro      float32 `json:"Xgyro" `      // [ rad/s ] Angular speed around X axis
	Ygyro      float32 `json:"Ygyro" `      // [ rad/s ] Angular speed around Y axis
	Zgyro      float32 `json:"Zgyro" `      // [ rad/s ] Angular speed around Z axis
	Lat        float32 `json:"Lat" `        // [ deg ] Latitude
	Lon        float32 `json:"Lon" `        // [ deg ] Longitude
	Alt        float32 `json:"Alt" `        // [ m ] Altitude
	StdDevHorz float32 `json:"StdDevHorz" ` // Horizontal position standard deviation
	StdDevVert float32 `json:"StdDevVert" ` // Vertical position standard deviation
	Vn         float32 `json:"Vn" `         // [ m/s ] True velocity in north direction in earth-fixed NED frame
	Ve         float32 `json:"Ve" `         // [ m/s ] True velocity in east direction in earth-fixed NED frame
	Vd         float32 `json:"Vd" `         // [ m/s ] True velocity in down direction in earth-fixed NED frame
}

SimState struct (generated typeinfo) Status of simulation environment, if used

func (*SimState) Dict

func (m *SimState) Dict() map[string]interface{}

ToMap (generated function)

func (*SimState) Marshal

func (m *SimState) Marshal() ([]byte, error)

Marshal (generated function)

func (SimState) MarshalEasyJSON added in v1.5.0

func (v SimState) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (SimState) MarshalJSON added in v1.5.0

func (v SimState) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*SimState) MsgID

func (m *SimState) MsgID() message.MessageID

MsgID (generated function)

func (*SimState) String

func (m *SimState) String() string

String (generated function)

func (*SimState) Unmarshal

func (m *SimState) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*SimState) UnmarshalEasyJSON added in v1.5.0

func (v *SimState) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*SimState) UnmarshalJSON added in v1.5.0

func (v *SimState) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Simstate

type Simstate struct {
	Roll  float32 `json:"Roll" `  // [ rad ] Roll angle.
	Pitch float32 `json:"Pitch" ` // [ rad ] Pitch angle.
	Yaw   float32 `json:"Yaw" `   // [ rad ] Yaw angle.
	Xacc  float32 `json:"Xacc" `  // [ m/s/s ] X acceleration.
	Yacc  float32 `json:"Yacc" `  // [ m/s/s ] Y acceleration.
	Zacc  float32 `json:"Zacc" `  // [ m/s/s ] Z acceleration.
	Xgyro float32 `json:"Xgyro" ` // [ rad/s ] Angular speed around X axis.
	Ygyro float32 `json:"Ygyro" ` // [ rad/s ] Angular speed around Y axis.
	Zgyro float32 `json:"Zgyro" ` // [ rad/s ] Angular speed around Z axis.
	Lat   int32   `json:"Lat" `   // [ degE7 ] Latitude.
	Lng   int32   `json:"Lng" `   // [ degE7 ] Longitude.
}

Simstate struct (generated typeinfo) Status of simulation environment, if used.

func (*Simstate) Dict

func (m *Simstate) Dict() map[string]interface{}

ToMap (generated function)

func (*Simstate) Marshal

func (m *Simstate) Marshal() ([]byte, error)

Marshal (generated function)

func (Simstate) MarshalEasyJSON added in v1.5.0

func (v Simstate) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Simstate) MarshalJSON added in v1.5.0

func (v Simstate) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Simstate) MsgID

func (m *Simstate) MsgID() message.MessageID

MsgID (generated function)

func (*Simstate) String

func (m *Simstate) String() string

String (generated function)

func (*Simstate) Unmarshal

func (m *Simstate) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Simstate) UnmarshalEasyJSON added in v1.5.0

func (v *Simstate) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Simstate) UnmarshalJSON added in v1.5.0

func (v *Simstate) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Statustext

type Statustext struct {
	Severity MAV_SEVERITY `json:"Severity" `      // Severity of status. Relies on the definitions within RFC-5424.
	Text     string       `json:"Text" len:"50" ` // Status text message, without null termination character
}

Statustext struct (generated typeinfo) Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz).

func (*Statustext) Dict

func (m *Statustext) Dict() map[string]interface{}

ToMap (generated function)

func (*Statustext) Marshal

func (m *Statustext) Marshal() ([]byte, error)

Marshal (generated function)

func (Statustext) MarshalEasyJSON added in v1.5.0

func (v Statustext) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Statustext) MarshalJSON added in v1.5.0

func (v Statustext) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Statustext) MsgID

func (m *Statustext) MsgID() message.MessageID

MsgID (generated function)

func (*Statustext) String

func (m *Statustext) String() string

String (generated function)

func (*Statustext) Unmarshal

func (m *Statustext) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Statustext) UnmarshalEasyJSON added in v1.5.0

func (v *Statustext) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Statustext) UnmarshalJSON added in v1.5.0

func (v *Statustext) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type SysStatus

type SysStatus struct {
	OnboardControlSensorsPresent MAV_SYS_STATUS_SENSOR `json:"OnboardControlSensorsPresent" ` // Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.
	OnboardControlSensorsEnabled MAV_SYS_STATUS_SENSOR `json:"OnboardControlSensorsEnabled" ` // Bitmap showing which onboard controllers and sensors are enabled:  Value of 0: not enabled. Value of 1: enabled.
	OnboardControlSensorsHealth  MAV_SYS_STATUS_SENSOR `json:"OnboardControlSensorsHealth" `  // Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.
	Load                         uint16                `json:"Load" `                         // [ d% ] Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000
	VoltageBattery               uint16                `json:"VoltageBattery" `               // [ mV ] Battery voltage, UINT16_MAX: Voltage not sent by autopilot
	CurrentBattery               int16                 `json:"CurrentBattery" `               // [ cA ] Battery current, -1: Current not sent by autopilot
	DropRateComm                 uint16                `json:"DropRateComm" `                 // [ c% ] Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
	ErrorsComm                   uint16                `json:"ErrorsComm" `                   // Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
	ErrorsCount1                 uint16                `json:"ErrorsCount1" `                 // Autopilot-specific errors
	ErrorsCount2                 uint16                `json:"ErrorsCount2" `                 // Autopilot-specific errors
	ErrorsCount3                 uint16                `json:"ErrorsCount3" `                 // Autopilot-specific errors
	ErrorsCount4                 uint16                `json:"ErrorsCount4" `                 // Autopilot-specific errors
	BatteryRemaining             int8                  `json:"BatteryRemaining" `             // [ % ] Battery energy remaining, -1: Battery remaining energy not sent by autopilot
}

SysStatus struct (generated typeinfo) The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows whether the system is currently active or not and if an emergency occurred. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occurred it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.

func (*SysStatus) Dict

func (m *SysStatus) Dict() map[string]interface{}

ToMap (generated function)

func (*SysStatus) Marshal

func (m *SysStatus) Marshal() ([]byte, error)

Marshal (generated function)

func (SysStatus) MarshalEasyJSON added in v1.5.0

func (v SysStatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (SysStatus) MarshalJSON added in v1.5.0

func (v SysStatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*SysStatus) MsgID

func (m *SysStatus) MsgID() message.MessageID

MsgID (generated function)

func (*SysStatus) String

func (m *SysStatus) String() string

String (generated function)

func (*SysStatus) Unmarshal

func (m *SysStatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*SysStatus) UnmarshalEasyJSON added in v1.5.0

func (v *SysStatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*SysStatus) UnmarshalJSON added in v1.5.0

func (v *SysStatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type SystemTime

type SystemTime struct {
	TimeUnixUsec uint64 `json:"TimeUnixUsec" ` // [ us ] Timestamp (UNIX epoch time).
	TimeBootMs   uint32 `json:"TimeBootMs" `   // [ ms ] Timestamp (time since system boot).
}

SystemTime struct (generated typeinfo) The system time is the time of the master clock, typically the computer clock of the main onboard computer.

func (*SystemTime) Dict

func (m *SystemTime) Dict() map[string]interface{}

ToMap (generated function)

func (*SystemTime) Marshal

func (m *SystemTime) Marshal() ([]byte, error)

Marshal (generated function)

func (SystemTime) MarshalEasyJSON added in v1.5.0

func (v SystemTime) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (SystemTime) MarshalJSON added in v1.5.0

func (v SystemTime) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*SystemTime) MsgID

func (m *SystemTime) MsgID() message.MessageID

MsgID (generated function)

func (*SystemTime) String

func (m *SystemTime) String() string

String (generated function)

func (*SystemTime) Unmarshal

func (m *SystemTime) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*SystemTime) UnmarshalEasyJSON added in v1.5.0

func (v *SystemTime) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*SystemTime) UnmarshalJSON added in v1.5.0

func (v *SystemTime) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type TRACKER_MODE

type TRACKER_MODE int

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

const (
	// TRACKER_MODE_MANUAL enum
	TRACKER_MODE_MANUAL TRACKER_MODE = 0
	// TRACKER_MODE_STOP enum
	TRACKER_MODE_STOP TRACKER_MODE = 1
	// TRACKER_MODE_SCAN enum
	TRACKER_MODE_SCAN TRACKER_MODE = 2
	// TRACKER_MODE_SERVO_TEST enum
	TRACKER_MODE_SERVO_TEST TRACKER_MODE = 3
	// TRACKER_MODE_AUTO enum
	TRACKER_MODE_AUTO TRACKER_MODE = 10
	// TRACKER_MODE_INITIALIZING enum
	TRACKER_MODE_INITIALIZING TRACKER_MODE = 16
)

func (TRACKER_MODE) Bitmask

func (e TRACKER_MODE) Bitmask() string

Bitmask return string representetion of intersects TRACKER_MODE enums

func (TRACKER_MODE) MarshalBinary

func (e TRACKER_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (TRACKER_MODE) String

func (e TRACKER_MODE) String() string

func (*TRACKER_MODE) UnmarshalBinary

func (e *TRACKER_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type TUNE_FORMAT

type TUNE_FORMAT int

TUNE_FORMAT type. Tune formats (used for vehicle buzzer/tone generation).

const (
	// TUNE_FORMAT_QBASIC1_1 enum. Format is QBasic 1.1 Play: https://www.qbasic.net/en/reference/qb11/Statement/PLAY-006.htm
	TUNE_FORMAT_QBASIC1_1 TUNE_FORMAT = 1
	// TUNE_FORMAT_MML_MODERN enum. Format is Modern Music Markup Language (MML): https://en.wikipedia.org/wiki/Music_Macro_Language#Modern_MML
	TUNE_FORMAT_MML_MODERN TUNE_FORMAT = 2
)

func (TUNE_FORMAT) Bitmask

func (e TUNE_FORMAT) Bitmask() string

Bitmask return string representetion of intersects TUNE_FORMAT enums

func (TUNE_FORMAT) MarshalBinary

func (e TUNE_FORMAT) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (TUNE_FORMAT) String

func (e TUNE_FORMAT) String() string

func (*TUNE_FORMAT) UnmarshalBinary

func (e *TUNE_FORMAT) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type TerrainCheck

type TerrainCheck struct {
	Lat int32 `json:"Lat" ` // [ degE7 ] Latitude
	Lon int32 `json:"Lon" ` // [ degE7 ] Longitude
}

TerrainCheck struct (generated typeinfo) Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission.

func (*TerrainCheck) Dict

func (m *TerrainCheck) Dict() map[string]interface{}

ToMap (generated function)

func (*TerrainCheck) Marshal

func (m *TerrainCheck) Marshal() ([]byte, error)

Marshal (generated function)

func (TerrainCheck) MarshalEasyJSON added in v1.5.0

func (v TerrainCheck) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (TerrainCheck) MarshalJSON added in v1.5.0

func (v TerrainCheck) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*TerrainCheck) MsgID

func (m *TerrainCheck) MsgID() message.MessageID

MsgID (generated function)

func (*TerrainCheck) String

func (m *TerrainCheck) String() string

String (generated function)

func (*TerrainCheck) Unmarshal

func (m *TerrainCheck) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*TerrainCheck) UnmarshalEasyJSON added in v1.5.0

func (v *TerrainCheck) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*TerrainCheck) UnmarshalJSON added in v1.5.0

func (v *TerrainCheck) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type TerrainData

type TerrainData struct {
	Lat         int32   `json:"Lat" `           // [ degE7 ] Latitude of SW corner of first grid
	Lon         int32   `json:"Lon" `           // [ degE7 ] Longitude of SW corner of first grid
	GridSpacing uint16  `json:"GridSpacing" `   // [ m ] Grid spacing
	Data        []int16 `json:"Data" len:"16" ` // [ m ] Terrain data MSL
	Gridbit     uint8   `json:"Gridbit" `       // bit within the terrain request mask
}

TerrainData struct (generated typeinfo) Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST. See terrain protocol docs: https://mavlink.io/en/services/terrain.html

func (*TerrainData) Dict

func (m *TerrainData) Dict() map[string]interface{}

ToMap (generated function)

func (*TerrainData) Marshal

func (m *TerrainData) Marshal() ([]byte, error)

Marshal (generated function)

func (TerrainData) MarshalEasyJSON added in v1.5.0

func (v TerrainData) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (TerrainData) MarshalJSON added in v1.5.0

func (v TerrainData) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*TerrainData) MsgID

func (m *TerrainData) MsgID() message.MessageID

MsgID (generated function)

func (*TerrainData) String

func (m *TerrainData) String() string

String (generated function)

func (*TerrainData) Unmarshal

func (m *TerrainData) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*TerrainData) UnmarshalEasyJSON added in v1.5.0

func (v *TerrainData) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*TerrainData) UnmarshalJSON added in v1.5.0

func (v *TerrainData) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type TerrainReport

type TerrainReport struct {
	Lat           int32   `json:"Lat" `           // [ degE7 ] Latitude
	Lon           int32   `json:"Lon" `           // [ degE7 ] Longitude
	TerrainHeight float32 `json:"TerrainHeight" ` // [ m ] Terrain height MSL
	CurrentHeight float32 `json:"CurrentHeight" ` // [ m ] Current vehicle height above lat/lon terrain height
	Spacing       uint16  `json:"Spacing" `       // grid spacing (zero if terrain at this location unavailable)
	Pending       uint16  `json:"Pending" `       // Number of 4x4 terrain blocks waiting to be received or read from disk
	Loaded        uint16  `json:"Loaded" `        // Number of 4x4 terrain blocks in memory
}

TerrainReport struct (generated typeinfo) Streamed from drone to report progress of terrain map download (initiated by TERRAIN_REQUEST), or sent as a response to a TERRAIN_CHECK request. See terrain protocol docs: https://mavlink.io/en/services/terrain.html

func (*TerrainReport) Dict

func (m *TerrainReport) Dict() map[string]interface{}

ToMap (generated function)

func (*TerrainReport) Marshal

func (m *TerrainReport) Marshal() ([]byte, error)

Marshal (generated function)

func (TerrainReport) MarshalEasyJSON added in v1.5.0

func (v TerrainReport) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (TerrainReport) MarshalJSON added in v1.5.0

func (v TerrainReport) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*TerrainReport) MsgID

func (m *TerrainReport) MsgID() message.MessageID

MsgID (generated function)

func (*TerrainReport) String

func (m *TerrainReport) String() string

String (generated function)

func (*TerrainReport) Unmarshal

func (m *TerrainReport) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*TerrainReport) UnmarshalEasyJSON added in v1.5.0

func (v *TerrainReport) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*TerrainReport) UnmarshalJSON added in v1.5.0

func (v *TerrainReport) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type TerrainRequest

type TerrainRequest struct {
	Mask        uint64 `json:"Mask" `        // Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)
	Lat         int32  `json:"Lat" `         // [ degE7 ] Latitude of SW corner of first grid
	Lon         int32  `json:"Lon" `         // [ degE7 ] Longitude of SW corner of first grid
	GridSpacing uint16 `json:"GridSpacing" ` // [ m ] Grid spacing
}

TerrainRequest struct (generated typeinfo) Request for terrain data and terrain status. See terrain protocol docs: https://mavlink.io/en/services/terrain.html

func (*TerrainRequest) Dict

func (m *TerrainRequest) Dict() map[string]interface{}

ToMap (generated function)

func (*TerrainRequest) Marshal

func (m *TerrainRequest) Marshal() ([]byte, error)

Marshal (generated function)

func (TerrainRequest) MarshalEasyJSON added in v1.5.0

func (v TerrainRequest) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (TerrainRequest) MarshalJSON added in v1.5.0

func (v TerrainRequest) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*TerrainRequest) MsgID

func (m *TerrainRequest) MsgID() message.MessageID

MsgID (generated function)

func (*TerrainRequest) String

func (m *TerrainRequest) String() string

String (generated function)

func (*TerrainRequest) Unmarshal

func (m *TerrainRequest) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*TerrainRequest) UnmarshalEasyJSON added in v1.5.0

func (v *TerrainRequest) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*TerrainRequest) UnmarshalJSON added in v1.5.0

func (v *TerrainRequest) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Timesync

type Timesync struct {
	Tc1 int64 `json:"Tc1" ` // Time sync timestamp 1
	Ts1 int64 `json:"Ts1" ` // Time sync timestamp 2
}

Timesync struct (generated typeinfo) Time synchronization message.

func (*Timesync) Dict

func (m *Timesync) Dict() map[string]interface{}

ToMap (generated function)

func (*Timesync) Marshal

func (m *Timesync) Marshal() ([]byte, error)

Marshal (generated function)

func (Timesync) MarshalEasyJSON added in v1.5.0

func (v Timesync) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Timesync) MarshalJSON added in v1.5.0

func (v Timesync) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Timesync) MsgID

func (m *Timesync) MsgID() message.MessageID

MsgID (generated function)

func (*Timesync) String

func (m *Timesync) String() string

String (generated function)

func (*Timesync) Unmarshal

func (m *Timesync) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Timesync) UnmarshalEasyJSON added in v1.5.0

func (v *Timesync) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Timesync) UnmarshalJSON added in v1.5.0

func (v *Timesync) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type UALBERTA_AUTOPILOT_MODE

type UALBERTA_AUTOPILOT_MODE int

UALBERTA_AUTOPILOT_MODE type. Available autopilot modes for ualberta uav

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

func (UALBERTA_AUTOPILOT_MODE) Bitmask

func (e UALBERTA_AUTOPILOT_MODE) Bitmask() string

Bitmask return string representetion of intersects UALBERTA_AUTOPILOT_MODE enums

func (UALBERTA_AUTOPILOT_MODE) MarshalBinary

func (e UALBERTA_AUTOPILOT_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (UALBERTA_AUTOPILOT_MODE) String

func (e UALBERTA_AUTOPILOT_MODE) String() string

func (*UALBERTA_AUTOPILOT_MODE) UnmarshalBinary

func (e *UALBERTA_AUTOPILOT_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type UALBERTA_NAV_MODE

type UALBERTA_NAV_MODE int

UALBERTA_NAV_MODE type. Navigation filter mode

const (
	// NAV_AHRS_INIT enum
	NAV_AHRS_INIT UALBERTA_NAV_MODE = 1
	// NAV_AHRS enum. AHRS mode
	NAV_AHRS UALBERTA_NAV_MODE = 2
	// NAV_INS_GPS_INIT enum. INS/GPS initialization mode
	NAV_INS_GPS_INIT UALBERTA_NAV_MODE = 3
	// NAV_INS_GPS enum. INS/GPS mode
	NAV_INS_GPS UALBERTA_NAV_MODE = 4
)

func (UALBERTA_NAV_MODE) Bitmask

func (e UALBERTA_NAV_MODE) Bitmask() string

Bitmask return string representetion of intersects UALBERTA_NAV_MODE enums

func (UALBERTA_NAV_MODE) MarshalBinary

func (e UALBERTA_NAV_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (UALBERTA_NAV_MODE) String

func (e UALBERTA_NAV_MODE) String() string

func (*UALBERTA_NAV_MODE) UnmarshalBinary

func (e *UALBERTA_NAV_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type UALBERTA_PILOT_MODE

type UALBERTA_PILOT_MODE int

UALBERTA_PILOT_MODE type. Mode currently commanded by pilot

const (
	// PILOT_MANUAL enum. sdf
	PILOT_MANUAL UALBERTA_PILOT_MODE = 1
	// PILOT_AUTO enum. dfs
	PILOT_AUTO UALBERTA_PILOT_MODE = 2
	// PILOT_ROTO enum. Rotomotion mode
	PILOT_ROTO UALBERTA_PILOT_MODE = 3
)

func (UALBERTA_PILOT_MODE) Bitmask

func (e UALBERTA_PILOT_MODE) Bitmask() string

Bitmask return string representetion of intersects UALBERTA_PILOT_MODE enums

func (UALBERTA_PILOT_MODE) MarshalBinary

func (e UALBERTA_PILOT_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (UALBERTA_PILOT_MODE) String

func (e UALBERTA_PILOT_MODE) String() string

func (*UALBERTA_PILOT_MODE) UnmarshalBinary

func (e *UALBERTA_PILOT_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type UAVCAN_NODE_HEALTH

type UAVCAN_NODE_HEALTH int

UAVCAN_NODE_HEALTH type. Generalized UAVCAN node health

const (
	// UAVCAN_NODE_HEALTH_OK enum. The node is functioning properly
	UAVCAN_NODE_HEALTH_OK UAVCAN_NODE_HEALTH = 0
	// UAVCAN_NODE_HEALTH_WARNING enum. A critical parameter went out of range or the node has encountered a minor failure
	UAVCAN_NODE_HEALTH_WARNING UAVCAN_NODE_HEALTH = 1
	// UAVCAN_NODE_HEALTH_ERROR enum. The node has encountered a major failure
	UAVCAN_NODE_HEALTH_ERROR UAVCAN_NODE_HEALTH = 2
	// UAVCAN_NODE_HEALTH_CRITICAL enum. The node has suffered a fatal malfunction
	UAVCAN_NODE_HEALTH_CRITICAL UAVCAN_NODE_HEALTH = 3
)

func (UAVCAN_NODE_HEALTH) Bitmask

func (e UAVCAN_NODE_HEALTH) Bitmask() string

Bitmask return string representetion of intersects UAVCAN_NODE_HEALTH enums

func (UAVCAN_NODE_HEALTH) MarshalBinary

func (e UAVCAN_NODE_HEALTH) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (UAVCAN_NODE_HEALTH) String

func (e UAVCAN_NODE_HEALTH) String() string

func (*UAVCAN_NODE_HEALTH) UnmarshalBinary

func (e *UAVCAN_NODE_HEALTH) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type UAVCAN_NODE_MODE

type UAVCAN_NODE_MODE int

UAVCAN_NODE_MODE type. Generalized UAVCAN node mode

const (
	// UAVCAN_NODE_MODE_OPERATIONAL enum. The node is performing its primary functions
	UAVCAN_NODE_MODE_OPERATIONAL UAVCAN_NODE_MODE = 0
	// UAVCAN_NODE_MODE_INITIALIZATION enum. The node is initializing; this mode is entered immediately after startup
	UAVCAN_NODE_MODE_INITIALIZATION UAVCAN_NODE_MODE = 1
	// UAVCAN_NODE_MODE_MAINTENANCE enum. The node is under maintenance
	UAVCAN_NODE_MODE_MAINTENANCE UAVCAN_NODE_MODE = 2
	// UAVCAN_NODE_MODE_SOFTWARE_UPDATE enum. The node is in the process of updating its software
	UAVCAN_NODE_MODE_SOFTWARE_UPDATE UAVCAN_NODE_MODE = 3
	// UAVCAN_NODE_MODE_OFFLINE enum. The node is no longer available online
	UAVCAN_NODE_MODE_OFFLINE UAVCAN_NODE_MODE = 7
)

func (UAVCAN_NODE_MODE) Bitmask

func (e UAVCAN_NODE_MODE) Bitmask() string

Bitmask return string representetion of intersects UAVCAN_NODE_MODE enums

func (UAVCAN_NODE_MODE) MarshalBinary

func (e UAVCAN_NODE_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (UAVCAN_NODE_MODE) String

func (e UAVCAN_NODE_MODE) String() string

func (*UAVCAN_NODE_MODE) UnmarshalBinary

func (e *UAVCAN_NODE_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type UAVIONIX_ADSB_EMERGENCY_STATUS

type UAVIONIX_ADSB_EMERGENCY_STATUS int

UAVIONIX_ADSB_EMERGENCY_STATUS type. Emergency status encoding

const (
	// UAVIONIX_ADSB_OUT_NO_EMERGENCY enum
	UAVIONIX_ADSB_OUT_NO_EMERGENCY UAVIONIX_ADSB_EMERGENCY_STATUS = 0
	// UAVIONIX_ADSB_OUT_GENERAL_EMERGENCY enum
	UAVIONIX_ADSB_OUT_GENERAL_EMERGENCY UAVIONIX_ADSB_EMERGENCY_STATUS = 1
	// UAVIONIX_ADSB_OUT_LIFEGUARD_EMERGENCY enum
	UAVIONIX_ADSB_OUT_LIFEGUARD_EMERGENCY UAVIONIX_ADSB_EMERGENCY_STATUS = 2
	// UAVIONIX_ADSB_OUT_MINIMUM_FUEL_EMERGENCY enum
	UAVIONIX_ADSB_OUT_MINIMUM_FUEL_EMERGENCY UAVIONIX_ADSB_EMERGENCY_STATUS = 3
	// UAVIONIX_ADSB_OUT_NO_COMM_EMERGENCY enum
	UAVIONIX_ADSB_OUT_NO_COMM_EMERGENCY UAVIONIX_ADSB_EMERGENCY_STATUS = 4
	// UAVIONIX_ADSB_OUT_UNLAWFUL_INTERFERANCE_EMERGENCY enum
	UAVIONIX_ADSB_OUT_UNLAWFUL_INTERFERANCE_EMERGENCY UAVIONIX_ADSB_EMERGENCY_STATUS = 5
	// UAVIONIX_ADSB_OUT_DOWNED_AIRCRAFT_EMERGENCY enum
	UAVIONIX_ADSB_OUT_DOWNED_AIRCRAFT_EMERGENCY UAVIONIX_ADSB_EMERGENCY_STATUS = 6
	// UAVIONIX_ADSB_OUT_RESERVED enum
	UAVIONIX_ADSB_OUT_RESERVED UAVIONIX_ADSB_EMERGENCY_STATUS = 7
)

func (UAVIONIX_ADSB_EMERGENCY_STATUS) Bitmask

Bitmask return string representetion of intersects UAVIONIX_ADSB_EMERGENCY_STATUS enums

func (UAVIONIX_ADSB_EMERGENCY_STATUS) MarshalBinary

func (e UAVIONIX_ADSB_EMERGENCY_STATUS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (UAVIONIX_ADSB_EMERGENCY_STATUS) String

func (*UAVIONIX_ADSB_EMERGENCY_STATUS) UnmarshalBinary

func (e *UAVIONIX_ADSB_EMERGENCY_STATUS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE

type UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE int

UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE type. Definitions for aircraft size

const (
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_NO_DATA enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_NO_DATA UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 0
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L15M_W23M enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L15M_W23M UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 1
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25M_W28P5M enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25M_W28P5M UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 2
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25_34M enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25_34M UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 3
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_33M enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_33M UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 4
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_38M enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_38M UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 5
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_39P5M enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_39P5M UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 6
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_45M enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_45M UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 7
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_45M enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_45M UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 8
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_52M enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_52M UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 9
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_59P5M enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_59P5M UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 10
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_67M enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_67M UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 11
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W72P5M enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W72P5M UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 12
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W80M enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W80M UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 13
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W80M enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W80M UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 14
	// UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W90M enum
	UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W90M UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE = 15
)

func (UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE) Bitmask

Bitmask return string representetion of intersects UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE enums

func (UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE) MarshalBinary

func (e UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE) String

func (*UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE) UnmarshalBinary

func (e *UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT

type UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT int

UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT type. GPS lataral offset encoding

const (
	// UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_NO_DATA enum
	UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_NO_DATA UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT = 0
	// UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_2M enum
	UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_2M UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT = 1
	// UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_4M enum
	UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_4M UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT = 2
	// UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_6M enum
	UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_6M UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT = 3
	// UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_0M enum
	UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_0M UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT = 4
	// UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_2M enum
	UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_2M UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT = 5
	// UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_4M enum
	UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_4M UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT = 6
	// UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_6M enum
	UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_6M UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT = 7
)

func (UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT) Bitmask

Bitmask return string representetion of intersects UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT enums

func (UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT) MarshalBinary

func (e UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT) String

func (*UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT) UnmarshalBinary

func (e *UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON

type UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON int

UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON type. GPS longitudinal offset encoding

const (
	// UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_NO_DATA enum
	UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_NO_DATA UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON = 0
	// UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_APPLIED_BY_SENSOR enum
	UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_APPLIED_BY_SENSOR UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON = 1
)

func (UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON) Bitmask

Bitmask return string representetion of intersects UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON enums

func (UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON) MarshalBinary

func (e UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON) String

func (*UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON) UnmarshalBinary

func (e *UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX

type UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX int

UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX type. Status for ADS-B transponder dynamic input

const (
	// UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_0 enum
	UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_0 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX = 0
	// UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_1 enum
	UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_1 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX = 1
	// UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_2D enum
	UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_2D UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX = 2
	// UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_3D enum
	UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_3D UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX = 3
	// UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_DGPS enum
	UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_DGPS UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX = 4
	// UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_RTK enum
	UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_RTK UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX = 5
)

func (UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX) Bitmask

Bitmask return string representetion of intersects UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX enums

func (UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX) MarshalBinary

func (e UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX) String

func (*UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX) UnmarshalBinary

func (e *UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type UAVIONIX_ADSB_OUT_DYNAMIC_STATE

type UAVIONIX_ADSB_OUT_DYNAMIC_STATE int

UAVIONIX_ADSB_OUT_DYNAMIC_STATE type. State flags for ADS-B transponder dynamic report

const (
	// UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE enum
	UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE UAVIONIX_ADSB_OUT_DYNAMIC_STATE = 1
	// UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED enum
	UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED UAVIONIX_ADSB_OUT_DYNAMIC_STATE = 2
	// UAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED enum
	UAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED UAVIONIX_ADSB_OUT_DYNAMIC_STATE = 4
	// UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND enum
	UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND UAVIONIX_ADSB_OUT_DYNAMIC_STATE = 8
	// UAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT enum
	UAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT UAVIONIX_ADSB_OUT_DYNAMIC_STATE = 16
)

func (UAVIONIX_ADSB_OUT_DYNAMIC_STATE) Bitmask

Bitmask return string representetion of intersects UAVIONIX_ADSB_OUT_DYNAMIC_STATE enums

func (UAVIONIX_ADSB_OUT_DYNAMIC_STATE) MarshalBinary

func (e UAVIONIX_ADSB_OUT_DYNAMIC_STATE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (UAVIONIX_ADSB_OUT_DYNAMIC_STATE) String

func (*UAVIONIX_ADSB_OUT_DYNAMIC_STATE) UnmarshalBinary

func (e *UAVIONIX_ADSB_OUT_DYNAMIC_STATE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type UAVIONIX_ADSB_OUT_RF_SELECT

type UAVIONIX_ADSB_OUT_RF_SELECT int

UAVIONIX_ADSB_OUT_RF_SELECT type. Transceiver RF control flags for ADS-B transponder dynamic reports

const (
	// UAVIONIX_ADSB_OUT_RF_SELECT_STANDBY enum
	UAVIONIX_ADSB_OUT_RF_SELECT_STANDBY UAVIONIX_ADSB_OUT_RF_SELECT = 0
	// UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED enum
	UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED UAVIONIX_ADSB_OUT_RF_SELECT = 1
	// UAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED enum
	UAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED UAVIONIX_ADSB_OUT_RF_SELECT = 2
)

func (UAVIONIX_ADSB_OUT_RF_SELECT) Bitmask

func (e UAVIONIX_ADSB_OUT_RF_SELECT) Bitmask() string

Bitmask return string representetion of intersects UAVIONIX_ADSB_OUT_RF_SELECT enums

func (UAVIONIX_ADSB_OUT_RF_SELECT) MarshalBinary

func (e UAVIONIX_ADSB_OUT_RF_SELECT) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (UAVIONIX_ADSB_OUT_RF_SELECT) String

func (*UAVIONIX_ADSB_OUT_RF_SELECT) UnmarshalBinary

func (e *UAVIONIX_ADSB_OUT_RF_SELECT) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type UAVIONIX_ADSB_RF_HEALTH

type UAVIONIX_ADSB_RF_HEALTH int

UAVIONIX_ADSB_RF_HEALTH type. Status flags for ADS-B transponder dynamic output

const (
	// UAVIONIX_ADSB_RF_HEALTH_INITIALIZING enum
	UAVIONIX_ADSB_RF_HEALTH_INITIALIZING UAVIONIX_ADSB_RF_HEALTH = 0
	// UAVIONIX_ADSB_RF_HEALTH_OK enum
	UAVIONIX_ADSB_RF_HEALTH_OK UAVIONIX_ADSB_RF_HEALTH = 1
	// UAVIONIX_ADSB_RF_HEALTH_FAIL_TX enum
	UAVIONIX_ADSB_RF_HEALTH_FAIL_TX UAVIONIX_ADSB_RF_HEALTH = 2
	// UAVIONIX_ADSB_RF_HEALTH_FAIL_RX enum
	UAVIONIX_ADSB_RF_HEALTH_FAIL_RX UAVIONIX_ADSB_RF_HEALTH = 16
)

func (UAVIONIX_ADSB_RF_HEALTH) Bitmask

func (e UAVIONIX_ADSB_RF_HEALTH) Bitmask() string

Bitmask return string representetion of intersects UAVIONIX_ADSB_RF_HEALTH enums

func (UAVIONIX_ADSB_RF_HEALTH) MarshalBinary

func (e UAVIONIX_ADSB_RF_HEALTH) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (UAVIONIX_ADSB_RF_HEALTH) String

func (e UAVIONIX_ADSB_RF_HEALTH) String() string

func (*UAVIONIX_ADSB_RF_HEALTH) UnmarshalBinary

func (e *UAVIONIX_ADSB_RF_HEALTH) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type UTM_DATA_AVAIL_FLAGS

type UTM_DATA_AVAIL_FLAGS int

UTM_DATA_AVAIL_FLAGS type. Flags for the global position report.

const (
	// UTM_DATA_AVAIL_FLAGS_TIME_VALID enum. The field time contains valid data
	UTM_DATA_AVAIL_FLAGS_TIME_VALID UTM_DATA_AVAIL_FLAGS = 1
	// UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE enum. The field uas_id contains valid data
	UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE UTM_DATA_AVAIL_FLAGS = 2
	// UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE enum. The fields lat, lon and h_acc contain valid data
	UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE UTM_DATA_AVAIL_FLAGS = 4
	// UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE enum. The fields alt and v_acc contain valid data
	UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE UTM_DATA_AVAIL_FLAGS = 8
	// UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE enum. The field relative_alt contains valid data
	UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE UTM_DATA_AVAIL_FLAGS = 16
	// UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE enum. The fields vx and vy contain valid data
	UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE UTM_DATA_AVAIL_FLAGS = 32
	// UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE enum. The field vz contains valid data
	UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE UTM_DATA_AVAIL_FLAGS = 64
	// UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE enum. The fields next_lat, next_lon and next_alt contain valid data
	UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE UTM_DATA_AVAIL_FLAGS = 128
)

func (UTM_DATA_AVAIL_FLAGS) Bitmask

func (e UTM_DATA_AVAIL_FLAGS) Bitmask() string

Bitmask return string representetion of intersects UTM_DATA_AVAIL_FLAGS enums

func (UTM_DATA_AVAIL_FLAGS) MarshalBinary

func (e UTM_DATA_AVAIL_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (UTM_DATA_AVAIL_FLAGS) String

func (e UTM_DATA_AVAIL_FLAGS) String() string

func (*UTM_DATA_AVAIL_FLAGS) UnmarshalBinary

func (e *UTM_DATA_AVAIL_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type UTM_FLIGHT_STATE

type UTM_FLIGHT_STATE int

UTM_FLIGHT_STATE type. Airborne status of UAS.

const (
	// UTM_FLIGHT_STATE_UNKNOWN enum. The flight state can't be determined
	UTM_FLIGHT_STATE_UNKNOWN UTM_FLIGHT_STATE = 1
	// UTM_FLIGHT_STATE_GROUND enum. UAS on ground
	UTM_FLIGHT_STATE_GROUND UTM_FLIGHT_STATE = 2
	// UTM_FLIGHT_STATE_AIRBORNE enum. UAS airborne
	UTM_FLIGHT_STATE_AIRBORNE UTM_FLIGHT_STATE = 3
	// UTM_FLIGHT_STATE_EMERGENCY enum. UAS is in an emergency flight state
	UTM_FLIGHT_STATE_EMERGENCY UTM_FLIGHT_STATE = 16
	// UTM_FLIGHT_STATE_NOCTRL enum. UAS has no active controls
	UTM_FLIGHT_STATE_NOCTRL UTM_FLIGHT_STATE = 32
)

func (UTM_FLIGHT_STATE) Bitmask

func (e UTM_FLIGHT_STATE) Bitmask() string

Bitmask return string representetion of intersects UTM_FLIGHT_STATE enums

func (UTM_FLIGHT_STATE) MarshalBinary

func (e UTM_FLIGHT_STATE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (UTM_FLIGHT_STATE) String

func (e UTM_FLIGHT_STATE) String() string

func (*UTM_FLIGHT_STATE) UnmarshalBinary

func (e *UTM_FLIGHT_STATE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type UalbertaSysStatus

type UalbertaSysStatus struct {
	Mode    uint8 `json:"Mode" `    // System mode, see UALBERTA_AUTOPILOT_MODE ENUM
	NavMode uint8 `json:"NavMode" ` // Navigation mode, see UALBERTA_NAV_MODE ENUM
	Pilot   uint8 `json:"Pilot" `   // Pilot mode, see UALBERTA_PILOT_MODE
}

UalbertaSysStatus struct (generated typeinfo) System status specific to ualberta uav

func (*UalbertaSysStatus) Dict

func (m *UalbertaSysStatus) Dict() map[string]interface{}

ToMap (generated function)

func (*UalbertaSysStatus) Marshal

func (m *UalbertaSysStatus) Marshal() ([]byte, error)

Marshal (generated function)

func (UalbertaSysStatus) MarshalEasyJSON added in v1.5.0

func (v UalbertaSysStatus) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (UalbertaSysStatus) MarshalJSON added in v1.5.0

func (v UalbertaSysStatus) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*UalbertaSysStatus) MsgID

func (m *UalbertaSysStatus) MsgID() message.MessageID

MsgID (generated function)

func (*UalbertaSysStatus) String

func (m *UalbertaSysStatus) String() string

String (generated function)

func (*UalbertaSysStatus) Unmarshal

func (m *UalbertaSysStatus) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*UalbertaSysStatus) UnmarshalEasyJSON added in v1.5.0

func (v *UalbertaSysStatus) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*UalbertaSysStatus) UnmarshalJSON added in v1.5.0

func (v *UalbertaSysStatus) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type V2Extension

type V2Extension struct {
	MessageType     uint16  `json:"MessageType" `       // A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.
	TargetNetwork   uint8   `json:"TargetNetwork" `     // Network ID (0 for broadcast)
	TargetSystem    uint8   `json:"TargetSystem" `      // System ID (0 for broadcast)
	TargetComponent uint8   `json:"TargetComponent" `   // Component ID (0 for broadcast)
	Payload         []uint8 `json:"Payload" len:"249" ` // Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification.
}

V2Extension struct (generated typeinfo) Message implementing parts of the V2 payload specs in V1 frames for transitional support.

func (*V2Extension) Dict

func (m *V2Extension) Dict() map[string]interface{}

ToMap (generated function)

func (*V2Extension) Marshal

func (m *V2Extension) Marshal() ([]byte, error)

Marshal (generated function)

func (V2Extension) MarshalEasyJSON added in v1.5.0

func (v V2Extension) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (V2Extension) MarshalJSON added in v1.5.0

func (v V2Extension) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*V2Extension) MsgID

func (m *V2Extension) MsgID() message.MessageID

MsgID (generated function)

func (*V2Extension) String

func (m *V2Extension) String() string

String (generated function)

func (*V2Extension) Unmarshal

func (m *V2Extension) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*V2Extension) UnmarshalEasyJSON added in v1.5.0

func (v *V2Extension) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*V2Extension) UnmarshalJSON added in v1.5.0

func (v *V2Extension) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type VIDEO_STREAM_STATUS_FLAGS

type VIDEO_STREAM_STATUS_FLAGS int

VIDEO_STREAM_STATUS_FLAGS type. Stream status flags (Bitmap)

const (
	// VIDEO_STREAM_STATUS_FLAGS_RUNNING enum. Stream is active (running)
	VIDEO_STREAM_STATUS_FLAGS_RUNNING VIDEO_STREAM_STATUS_FLAGS = 1
	// VIDEO_STREAM_STATUS_FLAGS_THERMAL enum. Stream is thermal imaging
	VIDEO_STREAM_STATUS_FLAGS_THERMAL VIDEO_STREAM_STATUS_FLAGS = 2
)

func (VIDEO_STREAM_STATUS_FLAGS) Bitmask

func (e VIDEO_STREAM_STATUS_FLAGS) Bitmask() string

Bitmask return string representetion of intersects VIDEO_STREAM_STATUS_FLAGS enums

func (VIDEO_STREAM_STATUS_FLAGS) MarshalBinary

func (e VIDEO_STREAM_STATUS_FLAGS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (VIDEO_STREAM_STATUS_FLAGS) String

func (e VIDEO_STREAM_STATUS_FLAGS) String() string

func (*VIDEO_STREAM_STATUS_FLAGS) UnmarshalBinary

func (e *VIDEO_STREAM_STATUS_FLAGS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type VIDEO_STREAM_TYPE

type VIDEO_STREAM_TYPE int

VIDEO_STREAM_TYPE type. Video stream types

const (
	// VIDEO_STREAM_TYPE_RTSP enum. Stream is RTSP
	VIDEO_STREAM_TYPE_RTSP VIDEO_STREAM_TYPE = 0
	// VIDEO_STREAM_TYPE_RTPUDP enum. Stream is RTP UDP (URI gives the port number)
	VIDEO_STREAM_TYPE_RTPUDP VIDEO_STREAM_TYPE = 1
	// VIDEO_STREAM_TYPE_TCP_MPEG enum. Stream is MPEG on TCP
	VIDEO_STREAM_TYPE_TCP_MPEG VIDEO_STREAM_TYPE = 2
	// VIDEO_STREAM_TYPE_MPEG_TS_H264 enum. Stream is h.264 on MPEG TS (URI gives the port number)
	VIDEO_STREAM_TYPE_MPEG_TS_H264 VIDEO_STREAM_TYPE = 3
)

func (VIDEO_STREAM_TYPE) Bitmask

func (e VIDEO_STREAM_TYPE) Bitmask() string

Bitmask return string representetion of intersects VIDEO_STREAM_TYPE enums

func (VIDEO_STREAM_TYPE) MarshalBinary

func (e VIDEO_STREAM_TYPE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (VIDEO_STREAM_TYPE) String

func (e VIDEO_STREAM_TYPE) String() string

func (*VIDEO_STREAM_TYPE) UnmarshalBinary

func (e *VIDEO_STREAM_TYPE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type VTOL_TRANSITION_HEADING

type VTOL_TRANSITION_HEADING int

VTOL_TRANSITION_HEADING type. Direction of VTOL transition

const (
	// VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT enum. Respect the heading configuration of the vehicle
	VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT VTOL_TRANSITION_HEADING = 0
	// VTOL_TRANSITION_HEADING_NEXT_WAYPOINT enum. Use the heading pointing towards the next waypoint
	VTOL_TRANSITION_HEADING_NEXT_WAYPOINT VTOL_TRANSITION_HEADING = 1
	// VTOL_TRANSITION_HEADING_TAKEOFF enum. Use the heading on takeoff (while sitting on the ground)
	VTOL_TRANSITION_HEADING_TAKEOFF VTOL_TRANSITION_HEADING = 2
	// VTOL_TRANSITION_HEADING_SPECIFIED enum. Use the specified heading in parameter 4
	VTOL_TRANSITION_HEADING_SPECIFIED VTOL_TRANSITION_HEADING = 3
	// VTOL_TRANSITION_HEADING_ANY enum. Use the current heading when reaching takeoff altitude (potentially facing the wind when weather-vaning is active)
	VTOL_TRANSITION_HEADING_ANY VTOL_TRANSITION_HEADING = 4
)

func (VTOL_TRANSITION_HEADING) Bitmask

func (e VTOL_TRANSITION_HEADING) Bitmask() string

Bitmask return string representetion of intersects VTOL_TRANSITION_HEADING enums

func (VTOL_TRANSITION_HEADING) MarshalBinary

func (e VTOL_TRANSITION_HEADING) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (VTOL_TRANSITION_HEADING) String

func (e VTOL_TRANSITION_HEADING) String() string

func (*VTOL_TRANSITION_HEADING) UnmarshalBinary

func (e *VTOL_TRANSITION_HEADING) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type VfrHud

type VfrHud struct {
	Airspeed    float32 `json:"Airspeed" `    // [ m/s ] Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed.
	Groundspeed float32 `json:"Groundspeed" ` // [ m/s ] Current ground speed.
	Alt         float32 `json:"Alt" `         // [ m ] Current altitude (MSL).
	Climb       float32 `json:"Climb" `       // [ m/s ] Current climb rate.
	Heading     int16   `json:"Heading" `     // [ deg ] Current heading in compass units (0-360, 0=north).
	Throttle    uint16  `json:"Throttle" `    // [ % ] Current throttle setting (0 to 100).
}

VfrHud struct (generated typeinfo) Metrics typically displayed on a HUD for fixed wing aircraft.

func (*VfrHud) Dict

func (m *VfrHud) Dict() map[string]interface{}

ToMap (generated function)

func (*VfrHud) Marshal

func (m *VfrHud) Marshal() ([]byte, error)

Marshal (generated function)

func (VfrHud) MarshalEasyJSON added in v1.5.0

func (v VfrHud) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (VfrHud) MarshalJSON added in v1.5.0

func (v VfrHud) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*VfrHud) MsgID

func (m *VfrHud) MsgID() message.MessageID

MsgID (generated function)

func (*VfrHud) String

func (m *VfrHud) String() string

String (generated function)

func (*VfrHud) Unmarshal

func (m *VfrHud) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*VfrHud) UnmarshalEasyJSON added in v1.5.0

func (v *VfrHud) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*VfrHud) UnmarshalJSON added in v1.5.0

func (v *VfrHud) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type Vibration

type Vibration struct {
	TimeUsec   uint64  `json:"TimeUsec" `   // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	VibrationX float32 `json:"VibrationX" ` // Vibration levels on X-axis
	VibrationY float32 `json:"VibrationY" ` // Vibration levels on Y-axis
	VibrationZ float32 `json:"VibrationZ" ` // Vibration levels on Z-axis
	Clipping0  uint32  `json:"Clipping0" `  // first accelerometer clipping count
	Clipping1  uint32  `json:"Clipping1" `  // second accelerometer clipping count
	Clipping2  uint32  `json:"Clipping2" `  // third accelerometer clipping count
}

Vibration struct (generated typeinfo) Vibration levels and accelerometer clipping

func (*Vibration) Dict

func (m *Vibration) Dict() map[string]interface{}

ToMap (generated function)

func (*Vibration) Marshal

func (m *Vibration) Marshal() ([]byte, error)

Marshal (generated function)

func (Vibration) MarshalEasyJSON added in v1.5.0

func (v Vibration) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Vibration) MarshalJSON added in v1.5.0

func (v Vibration) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Vibration) MsgID

func (m *Vibration) MsgID() message.MessageID

MsgID (generated function)

func (*Vibration) String

func (m *Vibration) String() string

String (generated function)

func (*Vibration) Unmarshal

func (m *Vibration) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Vibration) UnmarshalEasyJSON added in v1.5.0

func (v *Vibration) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Vibration) UnmarshalJSON added in v1.5.0

func (v *Vibration) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type ViconPositionEstimate

type ViconPositionEstimate struct {
	Usec  uint64  `json:"Usec" `  // [ us ] Timestamp (UNIX time or time since system boot)
	X     float32 `json:"X" `     // [ m ] Global X position
	Y     float32 `json:"Y" `     // [ m ] Global Y position
	Z     float32 `json:"Z" `     // [ m ] Global Z position
	Roll  float32 `json:"Roll" `  // [ rad ] Roll angle
	Pitch float32 `json:"Pitch" ` // [ rad ] Pitch angle
	Yaw   float32 `json:"Yaw" `   // [ rad ] Yaw angle
}

ViconPositionEstimate struct (generated typeinfo) Global position estimate from a Vicon motion system source.

func (*ViconPositionEstimate) Dict

func (m *ViconPositionEstimate) Dict() map[string]interface{}

ToMap (generated function)

func (*ViconPositionEstimate) Marshal

func (m *ViconPositionEstimate) Marshal() ([]byte, error)

Marshal (generated function)

func (ViconPositionEstimate) MarshalEasyJSON added in v1.5.0

func (v ViconPositionEstimate) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (ViconPositionEstimate) MarshalJSON added in v1.5.0

func (v ViconPositionEstimate) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*ViconPositionEstimate) MsgID

MsgID (generated function)

func (*ViconPositionEstimate) String

func (m *ViconPositionEstimate) String() string

String (generated function)

func (*ViconPositionEstimate) Unmarshal

func (m *ViconPositionEstimate) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*ViconPositionEstimate) UnmarshalEasyJSON added in v1.5.0

func (v *ViconPositionEstimate) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*ViconPositionEstimate) UnmarshalJSON added in v1.5.0

func (v *ViconPositionEstimate) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type VisionPositionEstimate

type VisionPositionEstimate struct {
	Usec  uint64  `json:"Usec" `  // [ us ] Timestamp (UNIX time or time since system boot)
	X     float32 `json:"X" `     // [ m ] Local X position
	Y     float32 `json:"Y" `     // [ m ] Local Y position
	Z     float32 `json:"Z" `     // [ m ] Local Z position
	Roll  float32 `json:"Roll" `  // [ rad ] Roll angle
	Pitch float32 `json:"Pitch" ` // [ rad ] Pitch angle
	Yaw   float32 `json:"Yaw" `   // [ rad ] Yaw angle
}

VisionPositionEstimate struct (generated typeinfo) Local position/attitude estimate from a vision source.

func (*VisionPositionEstimate) Dict

func (m *VisionPositionEstimate) Dict() map[string]interface{}

ToMap (generated function)

func (*VisionPositionEstimate) Marshal

func (m *VisionPositionEstimate) Marshal() ([]byte, error)

Marshal (generated function)

func (VisionPositionEstimate) MarshalEasyJSON added in v1.5.0

func (v VisionPositionEstimate) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (VisionPositionEstimate) MarshalJSON added in v1.5.0

func (v VisionPositionEstimate) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*VisionPositionEstimate) MsgID

MsgID (generated function)

func (*VisionPositionEstimate) String

func (m *VisionPositionEstimate) String() string

String (generated function)

func (*VisionPositionEstimate) Unmarshal

func (m *VisionPositionEstimate) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*VisionPositionEstimate) UnmarshalEasyJSON added in v1.5.0

func (v *VisionPositionEstimate) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*VisionPositionEstimate) UnmarshalJSON added in v1.5.0

func (v *VisionPositionEstimate) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type VisionSpeedEstimate

type VisionSpeedEstimate struct {
	Usec uint64  `json:"Usec" ` // [ us ] Timestamp (UNIX time or time since system boot)
	X    float32 `json:"X" `    // [ m/s ] Global X speed
	Y    float32 `json:"Y" `    // [ m/s ] Global Y speed
	Z    float32 `json:"Z" `    // [ m/s ] Global Z speed
}

VisionSpeedEstimate struct (generated typeinfo) Speed estimate from a vision source.

func (*VisionSpeedEstimate) Dict

func (m *VisionSpeedEstimate) Dict() map[string]interface{}

ToMap (generated function)

func (*VisionSpeedEstimate) Marshal

func (m *VisionSpeedEstimate) Marshal() ([]byte, error)

Marshal (generated function)

func (VisionSpeedEstimate) MarshalEasyJSON added in v1.5.0

func (v VisionSpeedEstimate) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (VisionSpeedEstimate) MarshalJSON added in v1.5.0

func (v VisionSpeedEstimate) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*VisionSpeedEstimate) MsgID

MsgID (generated function)

func (*VisionSpeedEstimate) String

func (m *VisionSpeedEstimate) String() string

String (generated function)

func (*VisionSpeedEstimate) Unmarshal

func (m *VisionSpeedEstimate) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*VisionSpeedEstimate) UnmarshalEasyJSON added in v1.5.0

func (v *VisionSpeedEstimate) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*VisionSpeedEstimate) UnmarshalJSON added in v1.5.0

func (v *VisionSpeedEstimate) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type WIFI_CONFIG_AP_MODE

type WIFI_CONFIG_AP_MODE int

WIFI_CONFIG_AP_MODE type. WiFi Mode.

const (
	// WIFI_CONFIG_AP_MODE_UNDEFINED enum. WiFi mode is undefined
	WIFI_CONFIG_AP_MODE_UNDEFINED WIFI_CONFIG_AP_MODE = 0
	// WIFI_CONFIG_AP_MODE_AP enum. WiFi configured as an access point
	WIFI_CONFIG_AP_MODE_AP WIFI_CONFIG_AP_MODE = 1
	// WIFI_CONFIG_AP_MODE_STATION enum. WiFi configured as a station connected to an existing local WiFi network
	WIFI_CONFIG_AP_MODE_STATION WIFI_CONFIG_AP_MODE = 2
	// WIFI_CONFIG_AP_MODE_DISABLED enum. WiFi disabled
	WIFI_CONFIG_AP_MODE_DISABLED WIFI_CONFIG_AP_MODE = 3
)

func (WIFI_CONFIG_AP_MODE) Bitmask

func (e WIFI_CONFIG_AP_MODE) Bitmask() string

Bitmask return string representetion of intersects WIFI_CONFIG_AP_MODE enums

func (WIFI_CONFIG_AP_MODE) MarshalBinary

func (e WIFI_CONFIG_AP_MODE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (WIFI_CONFIG_AP_MODE) String

func (e WIFI_CONFIG_AP_MODE) String() string

func (*WIFI_CONFIG_AP_MODE) UnmarshalBinary

func (e *WIFI_CONFIG_AP_MODE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type WIFI_CONFIG_AP_RESPONSE

type WIFI_CONFIG_AP_RESPONSE int

WIFI_CONFIG_AP_RESPONSE type. Possible responses from a WIFI_CONFIG_AP message.

const (
	// WIFI_CONFIG_AP_RESPONSE_UNDEFINED enum. Undefined response. Likely an indicative of a system that doesn't support this request
	WIFI_CONFIG_AP_RESPONSE_UNDEFINED WIFI_CONFIG_AP_RESPONSE = 0
	// WIFI_CONFIG_AP_RESPONSE_ACCEPTED enum. Changes accepted
	WIFI_CONFIG_AP_RESPONSE_ACCEPTED WIFI_CONFIG_AP_RESPONSE = 1
	// WIFI_CONFIG_AP_RESPONSE_REJECTED enum. Changes rejected
	WIFI_CONFIG_AP_RESPONSE_REJECTED WIFI_CONFIG_AP_RESPONSE = 2
	// WIFI_CONFIG_AP_RESPONSE_MODE_ERROR enum. Invalid Mode
	WIFI_CONFIG_AP_RESPONSE_MODE_ERROR WIFI_CONFIG_AP_RESPONSE = 3
	// WIFI_CONFIG_AP_RESPONSE_SSID_ERROR enum. Invalid SSID
	WIFI_CONFIG_AP_RESPONSE_SSID_ERROR WIFI_CONFIG_AP_RESPONSE = 4
	// WIFI_CONFIG_AP_RESPONSE_PASSWORD_ERROR enum. Invalid Password
	WIFI_CONFIG_AP_RESPONSE_PASSWORD_ERROR WIFI_CONFIG_AP_RESPONSE = 5
)

func (WIFI_CONFIG_AP_RESPONSE) Bitmask

func (e WIFI_CONFIG_AP_RESPONSE) Bitmask() string

Bitmask return string representetion of intersects WIFI_CONFIG_AP_RESPONSE enums

func (WIFI_CONFIG_AP_RESPONSE) MarshalBinary

func (e WIFI_CONFIG_AP_RESPONSE) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (WIFI_CONFIG_AP_RESPONSE) String

func (e WIFI_CONFIG_AP_RESPONSE) String() string

func (*WIFI_CONFIG_AP_RESPONSE) UnmarshalBinary

func (e *WIFI_CONFIG_AP_RESPONSE) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type WINCH_ACTIONS

type WINCH_ACTIONS int

WINCH_ACTIONS type. Winch actions.

const (
	// WINCH_RELAXED enum. Relax winch
	WINCH_RELAXED WINCH_ACTIONS = 0
	// WINCH_RELATIVE_LENGTH_CONTROL enum. Wind or unwind specified length of cable, optionally using specified rate
	WINCH_RELATIVE_LENGTH_CONTROL WINCH_ACTIONS = 1
	// WINCH_RATE_CONTROL enum. Wind or unwind cable at specified rate
	WINCH_RATE_CONTROL WINCH_ACTIONS = 2
)

func (WINCH_ACTIONS) Bitmask

func (e WINCH_ACTIONS) Bitmask() string

Bitmask return string representetion of intersects WINCH_ACTIONS enums

func (WINCH_ACTIONS) MarshalBinary

func (e WINCH_ACTIONS) MarshalBinary() (data []byte, err error)

MarshalBinary generic func

func (WINCH_ACTIONS) String

func (e WINCH_ACTIONS) String() string

func (*WINCH_ACTIONS) UnmarshalBinary

func (e *WINCH_ACTIONS) UnmarshalBinary(data []byte) error

UnmarshalBinary generic func

type Wind

type Wind struct {
	Direction float32 `json:"Direction" ` // [ deg ] Wind direction (that wind is coming from).
	Speed     float32 `json:"Speed" `     // [ m/s ] Wind speed in ground plane.
	SpeedZ    float32 `json:"SpeedZ" `    // [ m/s ] Vertical wind speed.
}

Wind struct (generated typeinfo) Wind estimation.

func (*Wind) Dict

func (m *Wind) Dict() map[string]interface{}

ToMap (generated function)

func (*Wind) Marshal

func (m *Wind) Marshal() ([]byte, error)

Marshal (generated function)

func (Wind) MarshalEasyJSON added in v1.5.0

func (v Wind) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (Wind) MarshalJSON added in v1.5.0

func (v Wind) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*Wind) MsgID

func (m *Wind) MsgID() message.MessageID

MsgID (generated function)

func (*Wind) String

func (m *Wind) String() string

String (generated function)

func (*Wind) Unmarshal

func (m *Wind) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*Wind) UnmarshalEasyJSON added in v1.5.0

func (v *Wind) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*Wind) UnmarshalJSON added in v1.5.0

func (v *Wind) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

type WindCov

type WindCov struct {
	TimeUsec      uint64  `json:"TimeUsec" `      // [ us ] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
	WindX         float32 `json:"WindX" `         // [ m/s ] Wind in X (NED) direction
	WindY         float32 `json:"WindY" `         // [ m/s ] Wind in Y (NED) direction
	WindZ         float32 `json:"WindZ" `         // [ m/s ] Wind in Z (NED) direction
	VarHoriz      float32 `json:"VarHoriz" `      // [ m/s ] Variability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate.
	VarVert       float32 `json:"VarVert" `       // [ m/s ] Variability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate.
	WindAlt       float32 `json:"WindAlt" `       // [ m ] Altitude (MSL) that this measurement was taken at
	HorizAccuracy float32 `json:"HorizAccuracy" ` // [ m ] Horizontal speed 1-STD accuracy
	VertAccuracy  float32 `json:"VertAccuracy" `  // [ m ] Vertical speed 1-STD accuracy
}

WindCov struct (generated typeinfo) Wind covariance estimate from vehicle.

func (*WindCov) Dict

func (m *WindCov) Dict() map[string]interface{}

ToMap (generated function)

func (*WindCov) Marshal

func (m *WindCov) Marshal() ([]byte, error)

Marshal (generated function)

func (WindCov) MarshalEasyJSON added in v1.5.0

func (v WindCov) MarshalEasyJSON(w *jwriter.Writer)

MarshalEasyJSON supports easyjson.Marshaler interface

func (WindCov) MarshalJSON added in v1.5.0

func (v WindCov) MarshalJSON() ([]byte, error)

MarshalJSON supports json.Marshaler interface

func (*WindCov) MsgID

func (m *WindCov) MsgID() message.MessageID

MsgID (generated function)

func (*WindCov) String

func (m *WindCov) String() string

String (generated function)

func (*WindCov) Unmarshal

func (m *WindCov) Unmarshal(data []byte) error

Unmarshal (generated function)

func (*WindCov) UnmarshalEasyJSON added in v1.5.0

func (v *WindCov) UnmarshalEasyJSON(l *jlexer.Lexer)

UnmarshalEasyJSON supports easyjson.Unmarshaler interface

func (*WindCov) UnmarshalJSON added in v1.5.0

func (v *WindCov) UnmarshalJSON(data []byte) error

UnmarshalJSON supports json.Unmarshaler interface

Jump to

Keyboard shortcuts

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