pixhawk

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 = "pixhawk"

	PROTOCOL_INCLUDE = common.PROTOCOL_NAME
)
View Source
const (
	DATA_TYPE_JPEG_IMAGE = 1 //
	DATA_TYPE_RAW_IMAGE  = 2 //
	DATA_TYPE_KINECT     = 3 //
)

DATA_TYPES: Content Types for data transmission handshake

View Source
const (
	MAV_CMD_DO_START_SEARCH  = 0 // Starts a search
	MAV_CMD_DO_FINISH_SEARCH = 0 // Starts a search
	MAV_CMD_NAV_SWEEP        = 0 // Starts a search
)

MAV_CMD:

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 AttitudeControl

type AttitudeControl struct {
	Roll         float32 // roll
	Pitch        float32 // pitch
	Yaw          float32 // yaw
	Thrust       float32 // thrust
	Target       uint8   // The system to be controlled
	RollManual   uint8   // roll control enabled auto:0, manual:1
	PitchManual  uint8   // pitch auto:0, manual:1
	YawManual    uint8   // yaw auto:0, manual:1
	ThrustManual uint8   // thrust auto:0, manual:1
}

func (*AttitudeControl) FieldsString

func (self *AttitudeControl) FieldsString() string

func (*AttitudeControl) String

func (self *AttitudeControl) String() string

func (*AttitudeControl) TypeCRCExtra

func (self *AttitudeControl) TypeCRCExtra() uint8

func (*AttitudeControl) TypeID

func (self *AttitudeControl) TypeID() uint8

func (*AttitudeControl) TypeName

func (self *AttitudeControl) TypeName() string

func (*AttitudeControl) TypeSize

func (self *AttitudeControl) TypeSize() uint8

type BriefFeature

type BriefFeature struct {
	X                     float32   // x position in m
	Y                     float32   // y position in m
	Z                     float32   // z position in m
	Response              float32   // Harris operator response at this location
	Size                  uint16    // Size in pixels
	Orientation           uint16    // Orientation
	OrientationAssignment uint8     // Orientation assignment 0: false, 1:true
	Descriptor            [32]uint8 // Descriptor
}

func (*BriefFeature) FieldsString

func (self *BriefFeature) FieldsString() string

func (*BriefFeature) String

func (self *BriefFeature) String() string

func (*BriefFeature) TypeCRCExtra

func (self *BriefFeature) TypeCRCExtra() uint8

func (*BriefFeature) TypeID

func (self *BriefFeature) TypeID() uint8

func (*BriefFeature) TypeName

func (self *BriefFeature) TypeName() string

func (*BriefFeature) TypeSize

func (self *BriefFeature) TypeSize() uint8

type Char100

type Char100 [100]byte

func (*Char100) String

func (chars *Char100) String() string

type Char147

type Char147 [147]byte

func (*Char147) String

func (chars *Char147) String() string

type Char26

type Char26 [26]byte

func (*Char26) String

func (chars *Char26) String() string

type Char32

type Char32 [32]byte

func (*Char32) String

func (chars *Char32) String() string

type DetectionStats

type DetectionStats struct {
	Detections        uint32  // Number of detections
	ClusterIters      uint32  // Number of cluster iterations
	BestScore         float32 // Best score
	BestLat           int32   // Latitude of the best detection * 1E7
	BestLon           int32   // Longitude of the best detection * 1E7
	BestAlt           int32   // Altitude of the best detection * 1E3
	BestDetectionId   uint32  // Best detection ID
	BestClusterId     uint32  // Best cluster ID
	BestClusterIterId uint32  // Best cluster ID
	ImagesDone        uint32  // Number of images already processed
	ImagesTodo        uint32  // Number of images still to process
	Fps               float32 // Average images per seconds processed
}

func (*DetectionStats) FieldsString

func (self *DetectionStats) FieldsString() string

func (*DetectionStats) String

func (self *DetectionStats) String() string

func (*DetectionStats) TypeCRCExtra

func (self *DetectionStats) TypeCRCExtra() uint8

func (*DetectionStats) TypeID

func (self *DetectionStats) TypeID() uint8

func (*DetectionStats) TypeName

func (self *DetectionStats) TypeName() string

func (*DetectionStats) TypeSize

func (self *DetectionStats) TypeSize() uint8

type ImageAvailable

type ImageAvailable struct {
	CamId       uint64  // Camera id
	Timestamp   uint64  // Timestamp
	ValidUntil  uint64  // Until which timestamp this buffer will stay valid
	ImgSeq      uint32  // The image sequence number
	ImgBufIndex uint32  // Position of the image in the buffer, starts with 0
	Key         uint32  // Shared memory area key
	Exposure    uint32  // Exposure time, in microseconds
	Gain        float32 // Camera gain
	Roll        float32 // Roll angle in rad
	Pitch       float32 // Pitch angle in rad
	Yaw         float32 // Yaw angle in rad
	LocalZ      float32 // Local frame Z coordinate (height over ground)
	Lat         float32 // GPS X coordinate
	Lon         float32 // GPS Y coordinate
	Alt         float32 // Global frame altitude
	GroundX     float32 // Ground truth X
	GroundY     float32 // Ground truth Y
	GroundZ     float32 // Ground truth Z
	Width       uint16  // Image width
	Height      uint16  // Image height
	Depth       uint16  // Image depth
	CamNo       uint8   // Camera # (starts with 0)
	Channels    uint8   // Image channels
}

func (*ImageAvailable) FieldsString

func (self *ImageAvailable) FieldsString() string

func (*ImageAvailable) String

func (self *ImageAvailable) String() string

func (*ImageAvailable) TypeCRCExtra

func (self *ImageAvailable) TypeCRCExtra() uint8

func (*ImageAvailable) TypeID

func (self *ImageAvailable) TypeID() uint8

func (*ImageAvailable) TypeName

func (self *ImageAvailable) TypeName() string

func (*ImageAvailable) TypeSize

func (self *ImageAvailable) TypeSize() uint8

type ImageTriggerControl

type ImageTriggerControl struct {
	Enable uint8 // 0 to disable, 1 to enable
}

func (*ImageTriggerControl) FieldsString

func (self *ImageTriggerControl) FieldsString() string

func (*ImageTriggerControl) String

func (self *ImageTriggerControl) String() string

func (*ImageTriggerControl) TypeCRCExtra

func (self *ImageTriggerControl) TypeCRCExtra() uint8

func (*ImageTriggerControl) TypeID

func (self *ImageTriggerControl) TypeID() uint8

func (*ImageTriggerControl) TypeName

func (self *ImageTriggerControl) TypeName() string

func (*ImageTriggerControl) TypeSize

func (self *ImageTriggerControl) TypeSize() uint8

type ImageTriggered

type ImageTriggered struct {
	Timestamp uint64  // Timestamp
	Seq       uint32  // IMU seq
	Roll      float32 // Roll angle in rad
	Pitch     float32 // Pitch angle in rad
	Yaw       float32 // Yaw angle in rad
	LocalZ    float32 // Local frame Z coordinate (height over ground)
	Lat       float32 // GPS X coordinate
	Lon       float32 // GPS Y coordinate
	Alt       float32 // Global frame altitude
	GroundX   float32 // Ground truth X
	GroundY   float32 // Ground truth Y
	GroundZ   float32 // Ground truth Z
}

func (*ImageTriggered) FieldsString

func (self *ImageTriggered) FieldsString() string

func (*ImageTriggered) String

func (self *ImageTriggered) String() string

func (*ImageTriggered) TypeCRCExtra

func (self *ImageTriggered) TypeCRCExtra() uint8

func (*ImageTriggered) TypeID

func (self *ImageTriggered) TypeID() uint8

func (*ImageTriggered) TypeName

func (self *ImageTriggered) TypeName() string

func (*ImageTriggered) TypeSize

func (self *ImageTriggered) TypeSize() uint8

type Marker

type Marker struct {
	X     float32 // x position
	Y     float32 // y position
	Z     float32 // z position
	Roll  float32 // roll orientation
	Pitch float32 // pitch orientation
	Yaw   float32 // yaw orientation
	Id    uint16  // ID
}

func (*Marker) FieldsString

func (self *Marker) FieldsString() string

func (*Marker) String

func (self *Marker) String() string

func (*Marker) TypeCRCExtra

func (self *Marker) TypeCRCExtra() uint8

func (*Marker) TypeID

func (self *Marker) TypeID() uint8

func (*Marker) TypeName

func (self *Marker) TypeName() string

func (*Marker) TypeSize

func (self *Marker) TypeSize() uint8

type OnboardHealth

type OnboardHealth struct {
	Uptime         uint32  // Uptime of system
	RamTotal       float32 // RAM size in GiB
	SwapTotal      float32 // Swap size in GiB
	DiskTotal      float32 // Disk total in GiB
	Temp           float32 // Temperature
	Voltage        float32 // Supply voltage V
	NetworkLoadIn  float32 // Network load inbound KiB/s
	NetworkLoadOut float32 // Network load outbound in KiB/s
	CpuFreq        uint16  // CPU frequency
	CpuLoad        uint8   // CPU load in percent
	RamUsage       uint8   // RAM usage in percent
	SwapUsage      uint8   // Swap usage in percent
	DiskHealth     int8    // Disk health (-1: N/A, 0: ERR, 1: RO, 2: RW)
	DiskUsage      uint8   // Disk usage in percent
}

func (*OnboardHealth) FieldsString

func (self *OnboardHealth) FieldsString() string

func (*OnboardHealth) String

func (self *OnboardHealth) String() string

func (*OnboardHealth) TypeCRCExtra

func (self *OnboardHealth) TypeCRCExtra() uint8

func (*OnboardHealth) TypeID

func (self *OnboardHealth) TypeID() uint8

func (*OnboardHealth) TypeName

func (self *OnboardHealth) TypeName() string

func (*OnboardHealth) TypeSize

func (self *OnboardHealth) TypeSize() uint8

type PatternDetected

type PatternDetected struct {
	Confidence float32 // Confidence of detection
	Type       uint8   // 0: Pattern, 1: Letter
	File       Char100 // Pattern file name
	Detected   uint8   // Accepted as true detection, 0 no, 1 yes
}

func (*PatternDetected) FieldsString

func (self *PatternDetected) FieldsString() string

func (*PatternDetected) String

func (self *PatternDetected) String() string

func (*PatternDetected) TypeCRCExtra

func (self *PatternDetected) TypeCRCExtra() uint8

func (*PatternDetected) TypeID

func (self *PatternDetected) TypeID() uint8

func (*PatternDetected) TypeName

func (self *PatternDetected) TypeName() string

func (*PatternDetected) TypeSize

func (self *PatternDetected) TypeSize() uint8

type PointOfInterest

type PointOfInterest struct {
	X                float32 // X Position
	Y                float32 // Y Position
	Z                float32 // Z Position
	Timeout          uint16  // 0: no timeout, >1: timeout in seconds
	Type             uint8   // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
	Color            uint8   // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
	CoordinateSystem uint8   // 0: global, 1:local
	Name             Char26  // POI name
}

Notifies the operator about a point of interest (POI). This can be anything detected by the

system. This generic message is intented to help interfacing to generic visualizations and to display
the POI on a map.

func (*PointOfInterest) FieldsString

func (self *PointOfInterest) FieldsString() string

func (*PointOfInterest) String

func (self *PointOfInterest) String() string

func (*PointOfInterest) TypeCRCExtra

func (self *PointOfInterest) TypeCRCExtra() uint8

func (*PointOfInterest) TypeID

func (self *PointOfInterest) TypeID() uint8

func (*PointOfInterest) TypeName

func (self *PointOfInterest) TypeName() string

func (*PointOfInterest) TypeSize

func (self *PointOfInterest) TypeSize() uint8

type PointOfInterestConnection

type PointOfInterestConnection struct {
	Xp1              float32 // X1 Position
	Yp1              float32 // Y1 Position
	Zp1              float32 // Z1 Position
	Xp2              float32 // X2 Position
	Yp2              float32 // Y2 Position
	Zp2              float32 // Z2 Position
	Timeout          uint16  // 0: no timeout, >1: timeout in seconds
	Type             uint8   // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
	Color            uint8   // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
	CoordinateSystem uint8   // 0: global, 1:local
	Name             Char26  // POI connection name
}

Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the

system. This generic message is intented to help interfacing to generic visualizations and to display
the POI on a map.

func (*PointOfInterestConnection) FieldsString

func (self *PointOfInterestConnection) FieldsString() string

func (*PointOfInterestConnection) String

func (self *PointOfInterestConnection) String() string

func (*PointOfInterestConnection) TypeCRCExtra

func (self *PointOfInterestConnection) TypeCRCExtra() uint8

func (*PointOfInterestConnection) TypeID

func (self *PointOfInterestConnection) TypeID() uint8

func (*PointOfInterestConnection) TypeName

func (self *PointOfInterestConnection) TypeName() string

func (*PointOfInterestConnection) TypeSize

func (self *PointOfInterestConnection) TypeSize() uint8

type PositionControlSetpoint

type PositionControlSetpoint struct {
	X   float32 // x position
	Y   float32 // y position
	Z   float32 // z position
	Yaw float32 // yaw orientation in radians, 0 = NORTH
	Id  uint16  // ID of waypoint, 0 for plain position
}

func (*PositionControlSetpoint) FieldsString

func (self *PositionControlSetpoint) FieldsString() string

func (*PositionControlSetpoint) String

func (self *PositionControlSetpoint) String() string

func (*PositionControlSetpoint) TypeCRCExtra

func (self *PositionControlSetpoint) TypeCRCExtra() uint8

func (*PositionControlSetpoint) TypeID

func (self *PositionControlSetpoint) TypeID() uint8

func (*PositionControlSetpoint) TypeName

func (self *PositionControlSetpoint) TypeName() string

func (*PositionControlSetpoint) TypeSize

func (self *PositionControlSetpoint) TypeSize() uint8

type RawAux

type RawAux struct {
	Baro int32  // Barometric pressure (hecto Pascal)
	Adc1 uint16 // ADC1 (J405 ADC3, LPC2148 AD0.6)
	Adc2 uint16 // ADC2 (J405 ADC5, LPC2148 AD0.2)
	Adc3 uint16 // ADC3 (J405 ADC6, LPC2148 AD0.1)
	Adc4 uint16 // ADC4 (J405 ADC7, LPC2148 AD1.3)
	Vbat uint16 // Battery voltage
	Temp int16  // Temperature (degrees celcius)
}

func (*RawAux) FieldsString

func (self *RawAux) FieldsString() string

func (*RawAux) String

func (self *RawAux) String() string

func (*RawAux) TypeCRCExtra

func (self *RawAux) TypeCRCExtra() uint8

func (*RawAux) TypeID

func (self *RawAux) TypeID() uint8

func (*RawAux) TypeName

func (self *RawAux) TypeName() string

func (*RawAux) TypeSize

func (self *RawAux) TypeSize() uint8

type SetCamShutter

type SetCamShutter struct {
	Gain       float32 // Camera gain
	Interval   uint16  // Shutter interval, in microseconds
	Exposure   uint16  // Exposure time, in microseconds
	CamNo      uint8   // Camera id
	CamMode    uint8   // Camera mode: 0 = auto, 1 = manual
	TriggerPin uint8   // Trigger pin, 0-3 for PtGrey FireFly
}

func (*SetCamShutter) FieldsString

func (self *SetCamShutter) FieldsString() string

func (*SetCamShutter) String

func (self *SetCamShutter) String() string

func (*SetCamShutter) TypeCRCExtra

func (self *SetCamShutter) TypeCRCExtra() uint8

func (*SetCamShutter) TypeID

func (self *SetCamShutter) TypeID() uint8

func (*SetCamShutter) TypeName

func (self *SetCamShutter) TypeName() string

func (*SetCamShutter) TypeSize

func (self *SetCamShutter) TypeSize() uint8

type SetPositionControlOffset

type SetPositionControlOffset struct {
	X               float32 // x position offset
	Y               float32 // y position offset
	Z               float32 // z position offset
	Yaw             float32 // yaw orientation offset in radians, 0 = NORTH
	TargetSystem    uint8   // System ID
	TargetComponent uint8   // Component ID
}

Message sent to the MAV to set a new offset from the currently controlled position

func (*SetPositionControlOffset) FieldsString

func (self *SetPositionControlOffset) FieldsString() string

func (*SetPositionControlOffset) String

func (self *SetPositionControlOffset) String() string

func (*SetPositionControlOffset) TypeCRCExtra

func (self *SetPositionControlOffset) TypeCRCExtra() uint8

func (*SetPositionControlOffset) TypeID

func (self *SetPositionControlOffset) TypeID() uint8

func (*SetPositionControlOffset) TypeName

func (self *SetPositionControlOffset) TypeName() string

func (*SetPositionControlOffset) TypeSize

func (self *SetPositionControlOffset) TypeSize() uint8

type WatchdogCommand

type WatchdogCommand struct {
	WatchdogId     uint16 // Watchdog ID
	ProcessId      uint16 // Process ID
	TargetSystemId uint8  // Target system ID
	CommandId      uint8  // Command ID
}

func (*WatchdogCommand) FieldsString

func (self *WatchdogCommand) FieldsString() string

func (*WatchdogCommand) String

func (self *WatchdogCommand) String() string

func (*WatchdogCommand) TypeCRCExtra

func (self *WatchdogCommand) TypeCRCExtra() uint8

func (*WatchdogCommand) TypeID

func (self *WatchdogCommand) TypeID() uint8

func (*WatchdogCommand) TypeName

func (self *WatchdogCommand) TypeName() string

func (*WatchdogCommand) TypeSize

func (self *WatchdogCommand) TypeSize() uint8

type WatchdogHeartbeat

type WatchdogHeartbeat struct {
	WatchdogId   uint16 // Watchdog ID
	ProcessCount uint16 // Number of processes
}

func (*WatchdogHeartbeat) FieldsString

func (self *WatchdogHeartbeat) FieldsString() string

func (*WatchdogHeartbeat) String

func (self *WatchdogHeartbeat) String() string

func (*WatchdogHeartbeat) TypeCRCExtra

func (self *WatchdogHeartbeat) TypeCRCExtra() uint8

func (*WatchdogHeartbeat) TypeID

func (self *WatchdogHeartbeat) TypeID() uint8

func (*WatchdogHeartbeat) TypeName

func (self *WatchdogHeartbeat) TypeName() string

func (*WatchdogHeartbeat) TypeSize

func (self *WatchdogHeartbeat) TypeSize() uint8

type WatchdogProcessInfo

type WatchdogProcessInfo struct {
	Timeout    int32   // Timeout (seconds)
	WatchdogId uint16  // Watchdog ID
	ProcessId  uint16  // Process ID
	Name       Char100 // Process name
	Arguments  Char147 // Process arguments
}

func (*WatchdogProcessInfo) FieldsString

func (self *WatchdogProcessInfo) FieldsString() string

func (*WatchdogProcessInfo) String

func (self *WatchdogProcessInfo) String() string

func (*WatchdogProcessInfo) TypeCRCExtra

func (self *WatchdogProcessInfo) TypeCRCExtra() uint8

func (*WatchdogProcessInfo) TypeID

func (self *WatchdogProcessInfo) TypeID() uint8

func (*WatchdogProcessInfo) TypeName

func (self *WatchdogProcessInfo) TypeName() string

func (*WatchdogProcessInfo) TypeSize

func (self *WatchdogProcessInfo) TypeSize() uint8

type WatchdogProcessStatus

type WatchdogProcessStatus struct {
	Pid        int32  // PID
	WatchdogId uint16 // Watchdog ID
	ProcessId  uint16 // Process ID
	Crashes    uint16 // Number of crashes
	State      uint8  // Is running / finished / suspended / crashed
	Muted      uint8  // Is muted
}

func (*WatchdogProcessStatus) FieldsString

func (self *WatchdogProcessStatus) FieldsString() string

func (*WatchdogProcessStatus) String

func (self *WatchdogProcessStatus) String() string

func (*WatchdogProcessStatus) TypeCRCExtra

func (self *WatchdogProcessStatus) TypeCRCExtra() uint8

func (*WatchdogProcessStatus) TypeID

func (self *WatchdogProcessStatus) TypeID() uint8

func (*WatchdogProcessStatus) TypeName

func (self *WatchdogProcessStatus) TypeName() string

func (*WatchdogProcessStatus) TypeSize

func (self *WatchdogProcessStatus) TypeSize() uint8

Jump to

Keyboard shortcuts

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