ardupilotmega

package
v0.0.0-...-4f9df97 Latest Latest
Warning

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

Go to latest
Published: Feb 11, 2016 License: MIT Imports: 3 Imported by: 0

Documentation

Index

Constants

View Source
const (
	PROTOCOL_NAME = "ardupilotmega"

	PROTOCOL_INCLUDE = common.PROTOCOL_NAME
)
View Source
const (
	MAV_CMD_DO_MOTOR_TEST = 209 // Mission command to perform motor test
	MAV_CMD_DO_GRIPPER    = 211 // Mission command to operate EPM gripper
)

MAV_CMD:

View Source
const (
	LIMITS_INIT       = 0 //  pre-initialization
	LIMITS_DISABLED   = 1 //  disabled
	LIMITS_ENABLED    = 2 //  checking limits
	LIMITS_TRIGGERED  = 3 //  a limit has been breached
	LIMITS_RECOVERING = 4 //  taking action eg. RTL
	LIMITS_RECOVERED  = 5 //  we're no longer in breach of a limit
)

LIMITS_STATE:

View Source
const (
	LIMIT_GPSLOCK  = 1 //  pre-initialization
	LIMIT_GEOFENCE = 2 //  disabled
	LIMIT_ALTITUDE = 4 //  checking limits
)

LIMIT_MODULE:

View Source
const (
	FAVORABLE_WIND   = 1 // Flag set when requiring favorable winds for landing.
	LAND_IMMEDIATELY = 2 // 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.
)

RALLY_FLAGS: Flags in RALLY_POINT message

View Source
const (
	PARACHUTE_DISABLE = 0 // Disable parachute release
	PARACHUTE_ENABLE  = 1 // Enable parachute release
	PARACHUTE_RELEASE = 2 // Release parachute
)

PARACHUTE_ACTION:

View Source
const (
	MOTOR_TEST_THROTTLE_PERCENT = 0 // throttle as a percentage from 0 ~ 100
	MOTOR_TEST_THROTTLE_PWM     = 1 // throttle as an absolute PWM value (normally in range of 1000~2000)
	MOTOR_TEST_THROTTLE_PILOT   = 2 // throttle pass-through from pilot's transmitter
)

MOTOR_TEST_THROTTLE_TYPE:

View Source
const (
	GRIPPER_ACTION_RELEASE = 0 // gripper release of cargo
	GRIPPER_ACTION_GRAB    = 1 // gripper grabs onto cargo
)

GRIPPER_ACTIONS: Gripper actions.

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

CAMERA_STATUS_TYPES:

View Source
const (
	VIDEO       = 1 // Shooting video, not stills
	BADEXPOSURE = 2 // Unable to achieve requested exposure (e.g. shutter speed too low)
	CLOSEDLOOP  = 3 // Closed loop feedback from camera, we know for sure it has successfully taken a picture
	OPENLOOP    = 4 // Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture
)

CAMERA_FEEDBACK_FLAGS:

Variables

This section is empty.

Functions

func Init

func Init()

Init initializes mavlink.ProtocolName, mavlink.ProtocolVersion, and mavlink.MessageFactory.

func MessageNameIDMap

func MessageNameIDMap() map[string]int

MessageNameIDMap returns a map from message name to message ID.

Types

type Ahrs

type Ahrs struct {
	Omegaix     float32 // X gyro drift estimate rad/s
	Omegaiy     float32 // Y gyro drift estimate rad/s
	Omegaiz     float32 // Z gyro drift estimate rad/s
	AccelWeight float32 // average accel_weight
	RenormVal   float32 // average renormalisation value
	ErrorRp     float32 // average error_roll_pitch value
	ErrorYaw    float32 // average error_yaw value
}

Status of DCM attitude estimator

func (*Ahrs) FieldsString

func (self *Ahrs) FieldsString() string

func (*Ahrs) String

func (self *Ahrs) String() string

func (*Ahrs) TypeCRCExtra

func (self *Ahrs) TypeCRCExtra() uint8

func (*Ahrs) TypeID

func (self *Ahrs) TypeID() uint8

func (*Ahrs) TypeName

func (self *Ahrs) TypeName() string

func (*Ahrs) TypeSize

func (self *Ahrs) TypeSize() uint8

type Ahrs2

type Ahrs2 struct {
	Roll     float32 // Roll angle (rad)
	Pitch    float32 // Pitch angle (rad)
	Yaw      float32 // Yaw angle (rad)
	Altitude float32 // Altitude (MSL)
	Lat      int32   // Latitude in degrees * 1E7
	Lng      int32   // Longitude in degrees * 1E7
}

Status of secondary AHRS filter if available

func (*Ahrs2) FieldsString

func (self *Ahrs2) FieldsString() string

func (*Ahrs2) String

func (self *Ahrs2) String() string

func (*Ahrs2) TypeCRCExtra

func (self *Ahrs2) TypeCRCExtra() uint8

func (*Ahrs2) TypeID

func (self *Ahrs2) TypeID() uint8

func (*Ahrs2) TypeName

func (self *Ahrs2) TypeName() string

func (*Ahrs2) TypeSize

func (self *Ahrs2) TypeSize() uint8

type Ahrs3

type Ahrs3 struct {
	Roll     float32 // Roll angle (rad)
	Pitch    float32 // Pitch angle (rad)
	Yaw      float32 // Yaw angle (rad)
	Altitude float32 // Altitude (MSL)
	Lat      int32   // Latitude in degrees * 1E7
	Lng      int32   // Longitude in degrees * 1E7
	V1       float32 // test variable1
	V2       float32 // test variable2
	V3       float32 // test variable3
	V4       float32 // test variable4
}

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

func (*Ahrs3) FieldsString

func (self *Ahrs3) FieldsString() string

func (*Ahrs3) String

func (self *Ahrs3) String() string

func (*Ahrs3) TypeCRCExtra

func (self *Ahrs3) TypeCRCExtra() uint8

func (*Ahrs3) TypeID

func (self *Ahrs3) TypeID() uint8

func (*Ahrs3) TypeName

func (self *Ahrs3) TypeName() string

func (*Ahrs3) TypeSize

func (self *Ahrs3) TypeSize() uint8

type AirspeedAutocal

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

Airspeed auto-calibration

func (*AirspeedAutocal) FieldsString

func (self *AirspeedAutocal) FieldsString() string

func (*AirspeedAutocal) String

func (self *AirspeedAutocal) String() string

func (*AirspeedAutocal) TypeCRCExtra

func (self *AirspeedAutocal) TypeCRCExtra() uint8

func (*AirspeedAutocal) TypeID

func (self *AirspeedAutocal) TypeID() uint8

func (*AirspeedAutocal) TypeName

func (self *AirspeedAutocal) TypeName() string

func (*AirspeedAutocal) TypeSize

func (self *AirspeedAutocal) TypeSize() uint8

type ApAdc

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

raw ADC output

func (*ApAdc) FieldsString

func (self *ApAdc) FieldsString() string

func (*ApAdc) String

func (self *ApAdc) String() string

func (*ApAdc) TypeCRCExtra

func (self *ApAdc) TypeCRCExtra() uint8

func (*ApAdc) TypeID

func (self *ApAdc) TypeID() uint8

func (*ApAdc) TypeName

func (self *ApAdc) TypeName() string

func (*ApAdc) TypeSize

func (self *ApAdc) TypeSize() uint8

type AutopilotVersionRequest

type AutopilotVersionRequest struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Request the autopilot version from the system/component.

func (*AutopilotVersionRequest) FieldsString

func (self *AutopilotVersionRequest) FieldsString() string

func (*AutopilotVersionRequest) String

func (self *AutopilotVersionRequest) String() string

func (*AutopilotVersionRequest) TypeCRCExtra

func (self *AutopilotVersionRequest) TypeCRCExtra() uint8

func (*AutopilotVersionRequest) TypeID

func (self *AutopilotVersionRequest) TypeID() uint8

func (*AutopilotVersionRequest) TypeName

func (self *AutopilotVersionRequest) TypeName() string

func (*AutopilotVersionRequest) TypeSize

func (self *AutopilotVersionRequest) TypeSize() uint8

type Battery2

type Battery2 struct {
	Voltage        uint16 // voltage in millivolts
	CurrentBattery int16  // Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
}

2nd Battery status

func (*Battery2) FieldsString

func (self *Battery2) FieldsString() string

func (*Battery2) String

func (self *Battery2) String() string

func (*Battery2) TypeCRCExtra

func (self *Battery2) TypeCRCExtra() uint8

func (*Battery2) TypeID

func (self *Battery2) TypeID() uint8

func (*Battery2) TypeName

func (self *Battery2) TypeName() string

func (*Battery2) TypeSize

func (self *Battery2) TypeSize() uint8

type CameraFeedback

type CameraFeedback struct {
	TimeUsec     uint64  // Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB)
	Lat          int32   // Latitude in (deg * 1E7)
	Lng          int32   // Longitude in (deg * 1E7)
	AltMsl       float32 // Altitude Absolute (meters AMSL)
	AltRel       float32 // Altitude Relative (meters above HOME location)
	Roll         float32 // Camera Roll angle (earth frame, degrees, +-180)
	Pitch        float32 // Camera Pitch angle (earth frame, degrees, +-180)
	Yaw          float32 // Camera Yaw (earth frame, degrees, 0-360, true)
	FocLen       float32 // Focal Length (mm)
	ImgIdx       uint16  // Image index
	TargetSystem uint8   // System ID
	CamIdx       uint8   // Camera ID
	Flags        uint8   // See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask
}

Camera Capture Feedback

func (*CameraFeedback) FieldsString

func (self *CameraFeedback) FieldsString() string

func (*CameraFeedback) String

func (self *CameraFeedback) String() string

func (*CameraFeedback) TypeCRCExtra

func (self *CameraFeedback) TypeCRCExtra() uint8

func (*CameraFeedback) TypeID

func (self *CameraFeedback) TypeID() uint8

func (*CameraFeedback) TypeName

func (self *CameraFeedback) TypeName() string

func (*CameraFeedback) TypeSize

func (self *CameraFeedback) TypeSize() uint8

type CameraStatus

type CameraStatus struct {
	TimeUsec     uint64  // Image timestamp (microseconds since UNIX epoch, according to camera clock)
	P1           float32 // Parameter 1 (meaning depends on event, see CAMERA_STATUS_TYPES enum)
	P2           float32 // Parameter 2 (meaning depends on event, see CAMERA_STATUS_TYPES enum)
	P3           float32 // Parameter 3 (meaning depends on event, see CAMERA_STATUS_TYPES enum)
	P4           float32 // Parameter 4 (meaning depends on event, see CAMERA_STATUS_TYPES enum)
	ImgIdx       uint16  // Image index
	TargetSystem uint8   // System ID
	CamIdx       uint8   // Camera ID
	EventId      uint8   // See CAMERA_STATUS_TYPES enum for definition of the bitmask
}

Camera Event

func (*CameraStatus) FieldsString

func (self *CameraStatus) FieldsString() string

func (*CameraStatus) String

func (self *CameraStatus) String() string

func (*CameraStatus) TypeCRCExtra

func (self *CameraStatus) TypeCRCExtra() uint8

func (*CameraStatus) TypeID

func (self *CameraStatus) TypeID() uint8

func (*CameraStatus) TypeName

func (self *CameraStatus) TypeName() string

func (*CameraStatus) TypeSize

func (self *CameraStatus) TypeSize() uint8

type Char16

type Char16 [16]byte

func (*Char16) String

func (chars *Char16) String() string

type Char32

type Char32 [32]byte

func (*Char32) String

func (chars *Char32) String() string

type Char64

type Char64 [64]byte

func (*Char64) String

func (chars *Char64) String() string

type Char96

type Char96 [96]byte

func (*Char96) String

func (chars *Char96) String() string

type CompassmotStatus

type CompassmotStatus struct {
	Current       float32 // current (amps)
	Compensationx float32 // Motor Compensation X
	Compensationy float32 // Motor Compensation Y
	Compensationz float32 // Motor Compensation Z
	Throttle      uint16  // throttle (percent*10)
	Interference  uint16  // interference (percent)
}

Status of compassmot calibration

func (*CompassmotStatus) FieldsString

func (self *CompassmotStatus) FieldsString() string

func (*CompassmotStatus) String

func (self *CompassmotStatus) String() string

func (*CompassmotStatus) TypeCRCExtra

func (self *CompassmotStatus) TypeCRCExtra() uint8

func (*CompassmotStatus) TypeID

func (self *CompassmotStatus) TypeID() uint8

func (*CompassmotStatus) TypeName

func (self *CompassmotStatus) TypeName() string

func (*CompassmotStatus) TypeSize

func (self *CompassmotStatus) TypeSize() uint8

type Data16

type Data16 struct {
	Type uint8     // data type
	Len  uint8     // data length
	Data [16]uint8 // raw data
}

Data packet, size 16

func (*Data16) FieldsString

func (self *Data16) FieldsString() string

func (*Data16) String

func (self *Data16) String() string

func (*Data16) TypeCRCExtra

func (self *Data16) TypeCRCExtra() uint8

func (*Data16) TypeID

func (self *Data16) TypeID() uint8

func (*Data16) TypeName

func (self *Data16) TypeName() string

func (*Data16) TypeSize

func (self *Data16) TypeSize() uint8

type Data32

type Data32 struct {
	Type uint8     // data type
	Len  uint8     // data length
	Data [32]uint8 // raw data
}

Data packet, size 32

func (*Data32) FieldsString

func (self *Data32) FieldsString() string

func (*Data32) String

func (self *Data32) String() string

func (*Data32) TypeCRCExtra

func (self *Data32) TypeCRCExtra() uint8

func (*Data32) TypeID

func (self *Data32) TypeID() uint8

func (*Data32) TypeName

func (self *Data32) TypeName() string

func (*Data32) TypeSize

func (self *Data32) TypeSize() uint8

type Data64

type Data64 struct {
	Type uint8     // data type
	Len  uint8     // data length
	Data [64]uint8 // raw data
}

Data packet, size 64

func (*Data64) FieldsString

func (self *Data64) FieldsString() string

func (*Data64) String

func (self *Data64) String() string

func (*Data64) TypeCRCExtra

func (self *Data64) TypeCRCExtra() uint8

func (*Data64) TypeID

func (self *Data64) TypeID() uint8

func (*Data64) TypeName

func (self *Data64) TypeName() string

func (*Data64) TypeSize

func (self *Data64) TypeSize() uint8

type Data96

type Data96 struct {
	Type uint8     // data type
	Len  uint8     // data length
	Data [96]uint8 // raw data
}

Data packet, size 96

func (*Data96) FieldsString

func (self *Data96) FieldsString() string

func (*Data96) String

func (self *Data96) String() string

func (*Data96) TypeCRCExtra

func (self *Data96) TypeCRCExtra() uint8

func (*Data96) TypeID

func (self *Data96) TypeID() uint8

func (*Data96) TypeName

func (self *Data96) TypeName() string

func (*Data96) TypeSize

func (self *Data96) TypeSize() uint8

type DigicamConfigure

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

Configure on-board Camera Control System.

func (*DigicamConfigure) FieldsString

func (self *DigicamConfigure) FieldsString() string

func (*DigicamConfigure) String

func (self *DigicamConfigure) String() string

func (*DigicamConfigure) TypeCRCExtra

func (self *DigicamConfigure) TypeCRCExtra() uint8

func (*DigicamConfigure) TypeID

func (self *DigicamConfigure) TypeID() uint8

func (*DigicamConfigure) TypeName

func (self *DigicamConfigure) TypeName() string

func (*DigicamConfigure) TypeSize

func (self *DigicamConfigure) TypeSize() uint8

type DigicamControl

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

Control on-board Camera Control System to take shots.

func (*DigicamControl) FieldsString

func (self *DigicamControl) FieldsString() string

func (*DigicamControl) String

func (self *DigicamControl) String() string

func (*DigicamControl) TypeCRCExtra

func (self *DigicamControl) TypeCRCExtra() uint8

func (*DigicamControl) TypeID

func (self *DigicamControl) TypeID() uint8

func (*DigicamControl) TypeName

func (self *DigicamControl) TypeName() string

func (*DigicamControl) TypeSize

func (self *DigicamControl) TypeSize() uint8

type FenceFetchPoint

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

Request a current fence point from MAV

func (*FenceFetchPoint) FieldsString

func (self *FenceFetchPoint) FieldsString() string

func (*FenceFetchPoint) String

func (self *FenceFetchPoint) String() string

func (*FenceFetchPoint) TypeCRCExtra

func (self *FenceFetchPoint) TypeCRCExtra() uint8

func (*FenceFetchPoint) TypeID

func (self *FenceFetchPoint) TypeID() uint8

func (*FenceFetchPoint) TypeName

func (self *FenceFetchPoint) TypeName() string

func (*FenceFetchPoint) TypeSize

func (self *FenceFetchPoint) TypeSize() uint8

type FencePoint

type FencePoint struct {
	Lat             float32 // Latitude of point
	Lng             float32 // Longitude of point
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
	Idx             uint8   // point index (first point is 1, 0 is for return point)
	Count           uint8   // total number of points (for sanity checking)
}

A fence point. Used to set a point when from

GCS -> MAV. Also used to return a point from MAV -> GCS

func (*FencePoint) FieldsString

func (self *FencePoint) FieldsString() string

func (*FencePoint) String

func (self *FencePoint) String() string

func (*FencePoint) TypeCRCExtra

func (self *FencePoint) TypeCRCExtra() uint8

func (*FencePoint) TypeID

func (self *FencePoint) TypeID() uint8

func (*FencePoint) TypeName

func (self *FencePoint) TypeName() string

func (*FencePoint) TypeSize

func (self *FencePoint) TypeSize() uint8

type FenceStatus

type FenceStatus struct {
	BreachTime   uint32 // time of last breach in milliseconds since boot
	BreachCount  uint16 // number of fence breaches
	BreachStatus uint8  // 0 if currently inside fence, 1 if outside
	BreachType   uint8  `enum:"FENCE_BREACH"` // last breach type (see FENCE_BREACH_* enum)
}

Status of geo-fencing. Sent in extended

status stream when fencing enabled

func (*FenceStatus) FieldsString

func (self *FenceStatus) FieldsString() string

func (*FenceStatus) String

func (self *FenceStatus) String() string

func (*FenceStatus) TypeCRCExtra

func (self *FenceStatus) TypeCRCExtra() uint8

func (*FenceStatus) TypeID

func (self *FenceStatus) TypeID() uint8

func (*FenceStatus) TypeName

func (self *FenceStatus) TypeName() string

func (*FenceStatus) TypeSize

func (self *FenceStatus) TypeSize() uint8

type GimbalControl

type GimbalControl struct {
	DemandedRateX   float32 // Demanded angular rate X, radians/s
	DemandedRateY   float32 // Demanded angular rate Y, radians/s
	DemandedRateZ   float32 // Demanded angular rate Z, radians/s
	GyroBiasX       float32 // Gyro bias X, radians/s
	GyroBiasY       float32 // Gyro bias Y, radians/s
	GyroBiasZ       float32 // Gyro bias Z, radians/s
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
}

Control packet from vehicle to MAVLink enabled gimbal. All values in gimbal sensor frame

func (*GimbalControl) FieldsString

func (self *GimbalControl) FieldsString() string

func (*GimbalControl) String

func (self *GimbalControl) String() string

func (*GimbalControl) TypeCRCExtra

func (self *GimbalControl) TypeCRCExtra() uint8

func (*GimbalControl) TypeID

func (self *GimbalControl) TypeID() uint8

func (*GimbalControl) TypeName

func (self *GimbalControl) TypeName() string

func (*GimbalControl) TypeSize

func (self *GimbalControl) TypeSize() uint8

type GimbalReport

type GimbalReport struct {
	DeltaTime       float32 // Time since last update (seconds)
	DeltaAngleX     float32 // Delta angle X, radians
	DeltaAngleY     float32 // Delta angle Y, radians
	DeltaAngleZ     float32 // Delta angle Z, radians
	DeltaVelocityX  float32 // Delta velocity X, m/s
	DeltaVelocityY  float32 // Delta velocity Y, m/s
	DeltaVelocityZ  float32 // Delta velocity Z, m/s
	JointRoll       float32 // Joint roll, radians
	JointPitch      float32 // Joint pitch, radians
	JointYaw        float32 // Joint yaw, radians
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
}

Report from MAVLink enabled gimbal to vehicle. The deltas are in gimbal sensor frame. Joint measurements assume a 312 ordering (azimuth, roll, pitch).

func (*GimbalReport) FieldsString

func (self *GimbalReport) FieldsString() string

func (*GimbalReport) String

func (self *GimbalReport) String() string

func (*GimbalReport) TypeCRCExtra

func (self *GimbalReport) TypeCRCExtra() uint8

func (*GimbalReport) TypeID

func (self *GimbalReport) TypeID() uint8

func (*GimbalReport) TypeName

func (self *GimbalReport) TypeName() string

func (*GimbalReport) TypeSize

func (self *GimbalReport) TypeSize() uint8

type Hwstatus

type Hwstatus struct {
	Vcc    uint16 // board voltage (mV)
	I2cerr uint8  // I2C error count
}

Status of key hardware

func (*Hwstatus) FieldsString

func (self *Hwstatus) FieldsString() string

func (*Hwstatus) String

func (self *Hwstatus) String() string

func (*Hwstatus) TypeCRCExtra

func (self *Hwstatus) TypeCRCExtra() uint8

func (*Hwstatus) TypeID

func (self *Hwstatus) TypeID() uint8

func (*Hwstatus) TypeName

func (self *Hwstatus) TypeName() string

func (*Hwstatus) TypeSize

func (self *Hwstatus) TypeSize() uint8

type LimitsStatus

type LimitsStatus struct {
	LastTrigger   uint32 // time of last breach in milliseconds since boot
	LastAction    uint32 // time of last recovery action in milliseconds since boot
	LastRecovery  uint32 // time of last successful recovery in milliseconds since boot
	LastClear     uint32 // time of last all-clear in milliseconds since boot
	BreachCount   uint16 // number of fence breaches
	LimitsState   uint8  `enum:"LIMITS_STATE"` // state of AP_Limits, (see enum LimitState, LIMITS_STATE)
	ModsEnabled   uint8  // AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE)
	ModsRequired  uint8  // AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE)
	ModsTriggered uint8  // AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE)
}

Status of AP_Limits. Sent in extended

status stream when AP_Limits is enabled

func (*LimitsStatus) FieldsString

func (self *LimitsStatus) FieldsString() string

func (*LimitsStatus) String

func (self *LimitsStatus) String() string

func (*LimitsStatus) TypeCRCExtra

func (self *LimitsStatus) TypeCRCExtra() uint8

func (*LimitsStatus) TypeID

func (self *LimitsStatus) TypeID() uint8

func (*LimitsStatus) TypeName

func (self *LimitsStatus) TypeName() string

func (*LimitsStatus) TypeSize

func (self *LimitsStatus) TypeSize() uint8

type Meminfo

type Meminfo struct {
	Brkval  uint16 // heap top
	Freemem uint16 // free memory
}

state of APM memory

func (*Meminfo) FieldsString

func (self *Meminfo) FieldsString() string

func (*Meminfo) String

func (self *Meminfo) String() string

func (*Meminfo) TypeCRCExtra

func (self *Meminfo) TypeCRCExtra() uint8

func (*Meminfo) TypeID

func (self *Meminfo) TypeID() uint8

func (*Meminfo) TypeName

func (self *Meminfo) TypeName() string

func (*Meminfo) TypeSize

func (self *Meminfo) TypeSize() uint8

type MountConfigure

type MountConfigure struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
	MountMode       uint8 `enum:"MAV_MOUNT_MODE"` // mount operating mode (see MAV_MOUNT_MODE enum)
	StabRoll        uint8 // (1 = yes, 0 = no)
	StabPitch       uint8 // (1 = yes, 0 = no)
	StabYaw         uint8 // (1 = yes, 0 = no)
}

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

func (*MountConfigure) FieldsString

func (self *MountConfigure) FieldsString() string

func (*MountConfigure) String

func (self *MountConfigure) String() string

func (*MountConfigure) TypeCRCExtra

func (self *MountConfigure) TypeCRCExtra() uint8

func (*MountConfigure) TypeID

func (self *MountConfigure) TypeID() uint8

func (*MountConfigure) TypeName

func (self *MountConfigure) TypeName() string

func (*MountConfigure) TypeSize

func (self *MountConfigure) TypeSize() uint8

type MountControl

type MountControl struct {
	InputA          int32 // pitch(deg*100) or lat, depending on mount mode
	InputB          int32 // roll(deg*100) or lon depending on mount mode
	InputC          int32 // yaw(deg*100) or alt (in cm) depending on mount mode
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
	SavePosition    uint8 // if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
}

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

func (*MountControl) FieldsString

func (self *MountControl) FieldsString() string

func (*MountControl) String

func (self *MountControl) String() string

func (*MountControl) TypeCRCExtra

func (self *MountControl) TypeCRCExtra() uint8

func (*MountControl) TypeID

func (self *MountControl) TypeID() uint8

func (*MountControl) TypeName

func (self *MountControl) TypeName() string

func (*MountControl) TypeSize

func (self *MountControl) TypeSize() uint8

type MountStatus

type MountStatus struct {
	PointingA       int32 // pitch(deg*100)
	PointingB       int32 // roll(deg*100)
	PointingC       int32 // yaw(deg*100)
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

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

func (*MountStatus) FieldsString

func (self *MountStatus) FieldsString() string

func (*MountStatus) String

func (self *MountStatus) String() string

func (*MountStatus) TypeCRCExtra

func (self *MountStatus) TypeCRCExtra() uint8

func (*MountStatus) TypeID

func (self *MountStatus) TypeID() uint8

func (*MountStatus) TypeName

func (self *MountStatus) TypeName() string

func (*MountStatus) TypeSize

func (self *MountStatus) TypeSize() uint8

type Radio

type Radio struct {
	Rxerrors uint16 // receive errors
	Fixed    uint16 // count of error corrected packets
	Rssi     uint8  // local signal strength
	Remrssi  uint8  // remote signal strength
	Txbuf    uint8  // how full the tx buffer is as a percentage
	Noise    uint8  // background noise level
	Remnoise uint8  // remote background noise level
}

Status generated by radio

func (*Radio) FieldsString

func (self *Radio) FieldsString() string

func (*Radio) String

func (self *Radio) String() string

func (*Radio) TypeCRCExtra

func (self *Radio) TypeCRCExtra() uint8

func (*Radio) TypeID

func (self *Radio) TypeID() uint8

func (*Radio) TypeName

func (self *Radio) TypeName() string

func (*Radio) TypeSize

func (self *Radio) TypeSize() uint8

type RallyFetchPoint

type RallyFetchPoint struct {
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
	Idx             uint8 // point index (first point is 0)
}

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) FieldsString

func (self *RallyFetchPoint) FieldsString() string

func (*RallyFetchPoint) String

func (self *RallyFetchPoint) String() string

func (*RallyFetchPoint) TypeCRCExtra

func (self *RallyFetchPoint) TypeCRCExtra() uint8

func (*RallyFetchPoint) TypeID

func (self *RallyFetchPoint) TypeID() uint8

func (*RallyFetchPoint) TypeName

func (self *RallyFetchPoint) TypeName() string

func (*RallyFetchPoint) TypeSize

func (self *RallyFetchPoint) TypeSize() uint8

type RallyPoint

type RallyPoint struct {
	Lat             int32  // Latitude of point in degrees * 1E7
	Lng             int32  // Longitude of point in degrees * 1E7
	Alt             int16  // Transit / loiter altitude in meters relative to home
	BreakAlt        int16  // Break altitude in meters relative to home
	LandDir         uint16 // Heading to aim for when landing. In centi-degrees.
	TargetSystem    uint8  // System ID
	TargetComponent uint8  // Component ID
	Idx             uint8  // point index (first point is 0)
	Count           uint8  // total number of points (for sanity checking)
	Flags           uint8  // See RALLY_FLAGS enum for definition of the bitmask.
}

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

func (*RallyPoint) FieldsString

func (self *RallyPoint) FieldsString() string

func (*RallyPoint) String

func (self *RallyPoint) String() string

func (*RallyPoint) TypeCRCExtra

func (self *RallyPoint) TypeCRCExtra() uint8

func (*RallyPoint) TypeID

func (self *RallyPoint) TypeID() uint8

func (*RallyPoint) TypeName

func (self *RallyPoint) TypeName() string

func (*RallyPoint) TypeSize

func (self *RallyPoint) TypeSize() uint8

type Rangefinder

type Rangefinder struct {
	Distance float32 // distance in meters
	Voltage  float32 // raw voltage if available, zero otherwise
}

Rangefinder reporting

func (*Rangefinder) FieldsString

func (self *Rangefinder) FieldsString() string

func (*Rangefinder) String

func (self *Rangefinder) String() string

func (*Rangefinder) TypeCRCExtra

func (self *Rangefinder) TypeCRCExtra() uint8

func (*Rangefinder) TypeID

func (self *Rangefinder) TypeID() uint8

func (*Rangefinder) TypeName

func (self *Rangefinder) TypeName() string

func (*Rangefinder) TypeSize

func (self *Rangefinder) TypeSize() uint8

type SensorOffsets

type SensorOffsets struct {
	MagDeclination float32 // magnetic declination (radians)
	RawPress       int32   // raw pressure from barometer
	RawTemp        int32   // raw temperature from barometer
	GyroCalX       float32 // gyro X calibration
	GyroCalY       float32 // gyro Y calibration
	GyroCalZ       float32 // gyro Z calibration
	AccelCalX      float32 // accel X calibration
	AccelCalY      float32 // accel Y calibration
	AccelCalZ      float32 // accel Z calibration
	MagOfsX        int16   // magnetometer X offset
	MagOfsY        int16   // magnetometer Y offset
	MagOfsZ        int16   // magnetometer Z offset
}

Offsets and calibrations values for hardware

sensors. This makes it easier to debug the calibration process.

func (*SensorOffsets) FieldsString

func (self *SensorOffsets) FieldsString() string

func (*SensorOffsets) String

func (self *SensorOffsets) String() string

func (*SensorOffsets) TypeCRCExtra

func (self *SensorOffsets) TypeCRCExtra() uint8

func (*SensorOffsets) TypeID

func (self *SensorOffsets) TypeID() uint8

func (*SensorOffsets) TypeName

func (self *SensorOffsets) TypeName() string

func (*SensorOffsets) TypeSize

func (self *SensorOffsets) TypeSize() uint8

type SetMagOffsets

type SetMagOffsets struct {
	MagOfsX         int16 // magnetometer X offset
	MagOfsY         int16 // magnetometer Y offset
	MagOfsZ         int16 // magnetometer Z offset
	TargetSystem    uint8 // System ID
	TargetComponent uint8 // Component ID
}

Deprecated. Use MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS instead. Set the magnetometer offsets

func (*SetMagOffsets) FieldsString

func (self *SetMagOffsets) FieldsString() string

func (*SetMagOffsets) String

func (self *SetMagOffsets) String() string

func (*SetMagOffsets) TypeCRCExtra

func (self *SetMagOffsets) TypeCRCExtra() uint8

func (*SetMagOffsets) TypeID

func (self *SetMagOffsets) TypeID() uint8

func (*SetMagOffsets) TypeName

func (self *SetMagOffsets) TypeName() string

func (*SetMagOffsets) TypeSize

func (self *SetMagOffsets) TypeSize() uint8

type Simstate

type Simstate struct {
	Roll  float32 // Roll angle (rad)
	Pitch float32 // Pitch angle (rad)
	Yaw   float32 // Yaw angle (rad)
	Xacc  float32 // X acceleration m/s/s
	Yacc  float32 // Y acceleration m/s/s
	Zacc  float32 // Z acceleration m/s/s
	Xgyro float32 // Angular speed around X axis rad/s
	Ygyro float32 // Angular speed around Y axis rad/s
	Zgyro float32 // Angular speed around Z axis rad/s
	Lat   int32   // Latitude in degrees * 1E7
	Lng   int32   // Longitude in degrees * 1E7
}

Status of simulation environment, if used

func (*Simstate) FieldsString

func (self *Simstate) FieldsString() string

func (*Simstate) String

func (self *Simstate) String() string

func (*Simstate) TypeCRCExtra

func (self *Simstate) TypeCRCExtra() uint8

func (*Simstate) TypeID

func (self *Simstate) TypeID() uint8

func (*Simstate) TypeName

func (self *Simstate) TypeName() string

func (*Simstate) TypeSize

func (self *Simstate) TypeSize() uint8

type Wind

type Wind struct {
	Direction float32 // wind direction that wind is coming from (degrees)
	Speed     float32 // wind speed in ground plane (m/s)
	SpeedZ    float32 // vertical wind speed (m/s)
}

Wind estimation

func (*Wind) FieldsString

func (self *Wind) FieldsString() string

func (*Wind) String

func (self *Wind) String() string

func (*Wind) TypeCRCExtra

func (self *Wind) TypeCRCExtra() uint8

func (*Wind) TypeID

func (self *Wind) TypeID() uint8

func (*Wind) TypeName

func (self *Wind) TypeName() string

func (*Wind) TypeSize

func (self *Wind) TypeSize() uint8

Jump to

Keyboard shortcuts

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