Documentation ¶
Index ¶
- Constants
- type Dialect
- type NAVFilterBias
- func (m *NAVFilterBias) GetDialect() string
- func (m *NAVFilterBias) GetID() uint32
- func (m *NAVFilterBias) GetMessageName() string
- func (m *NAVFilterBias) GetVersion() int
- func (m *NAVFilterBias) HasExtensionFields() bool
- func (m *NAVFilterBias) Read(frame mavlink2.Frame) (err error)
- func (m *NAVFilterBias) String() string
- func (m *NAVFilterBias) Write(version int) (output []byte, err error)
- type RadioCalibration
- func (m *RadioCalibration) GetDialect() string
- func (m *RadioCalibration) GetID() uint32
- func (m *RadioCalibration) GetMessageName() string
- func (m *RadioCalibration) GetVersion() int
- func (m *RadioCalibration) HasExtensionFields() bool
- func (m *RadioCalibration) Read(frame mavlink2.Frame) (err error)
- func (m *RadioCalibration) String() string
- func (m *RadioCalibration) Write(version int) (output []byte, err error)
- type UalbertaSysStatus
- func (m *UalbertaSysStatus) GetDialect() string
- func (m *UalbertaSysStatus) GetID() uint32
- func (m *UalbertaSysStatus) GetMessageName() string
- func (m *UalbertaSysStatus) GetVersion() int
- func (m *UalbertaSysStatus) HasExtensionFields() bool
- func (m *UalbertaSysStatus) Read(frame mavlink2.Frame) (err error)
- func (m *UalbertaSysStatus) String() string
- func (m *UalbertaSysStatus) Write(version int) (output []byte, err error)
Constants ¶
const ( /*ModeManualDirect - Raw input pulse widts sent to output */ ModeManualDirect = 1 /*ModeManualScaled - Inputs are normalized using calibration, the converted back to raw pulse widths for output */ ModeManualScaled = 2 /*ModeAutoPIDAtt - dfsdfs */ ModeAutoPIDAtt = 3 /*ModeAutoPIDVel - dfsfds */ ModeAutoPIDVel = 4 /*ModeAutoPIDPos - dfsdfsdfs */ ModeAutoPIDPos = 5 /*UalbertaAutopilotModeEnumEnd - */ UalbertaAutopilotModeEnumEnd = 6 )
UALBERTA_AUTOPILOT_MODE - Available autopilot modes for ualberta uav
const ( /*NAVAHRSInit - */ NAVAHRSInit = 1 /*NAVAHRS - AHRS mode */ NAVAHRS = 2 /*NAVInsGPSInit - INS/GPS initialization mode */ NAVInsGPSInit = 3 /*NAVInsGPS - INS/GPS mode */ NAVInsGPS = 4 /*UalbertaNAVModeEnumEnd - */ UalbertaNAVModeEnumEnd = 5 )
UALBERTA_NAV_MODE - Navigation filter mode
const ( /*PilotManual - sdf */ PilotManual = 1 /*PilotAuto - dfs */ PilotAuto = 2 /*PilotRoto - Rotomotion mode */ PilotRoto = 3 /*UalbertaPilotModeEnumEnd - */ UalbertaPilotModeEnumEnd = 4 )
UALBERTA_PILOT_MODE - Mode currently commanded by pilot
Variables ¶
This section is empty.
Functions ¶
This section is empty.
Types ¶
type Dialect ¶
type Dialect struct{}
Dialect represents a collection of MAVLink messages
func (Dialect) GetMessage ¶
GetMessage extracts and parses the message contained in the Frame
type NAVFilterBias ¶
type NAVFilterBias struct { /*Usec Timestamp (microseconds) */ Usec uint64 /*Accel0 b_f[0] */ Accel0 float32 /*Accel1 b_f[1] */ Accel1 float32 /*Accel2 b_f[2] */ Accel2 float32 /*Gyro0 b_f[0] */ Gyro0 float32 /*Gyro1 b_f[1] */ Gyro1 float32 /*Gyro2 b_f[2] */ Gyro2 float32 /*HasExtensionFieldValues indicates if this message has any extensions and */ HasExtensionFieldValues bool }
NAVFilterBias Accelerometer and Gyro biases from the navigation filter
func (*NAVFilterBias) GetDialect ¶
func (m *NAVFilterBias) GetDialect() string
GetDialect gets the name of the dialect that defines the Message
func (*NAVFilterBias) GetID ¶
func (m *NAVFilterBias) GetID() uint32
GetID gets the ID of the Message
func (*NAVFilterBias) GetMessageName ¶
func (m *NAVFilterBias) GetMessageName() string
GetMessageName gets the name of the Message
func (*NAVFilterBias) GetVersion ¶
func (m *NAVFilterBias) GetVersion() int
GetVersion gets the MAVLink version of the Message contents
func (*NAVFilterBias) HasExtensionFields ¶
func (m *NAVFilterBias) HasExtensionFields() bool
HasExtensionFields returns true if the message definition contained extensions; false otherwise
func (*NAVFilterBias) Read ¶
func (m *NAVFilterBias) Read(frame mavlink2.Frame) (err error)
Read sets the field values of the message from the raw message payload
func (*NAVFilterBias) String ¶
func (m *NAVFilterBias) String() string
type RadioCalibration ¶
type RadioCalibration struct { /*Aileron Aileron setpoints: left, center, right */ Aileron [3]uint16 /*Elevator Elevator setpoints: nose down, center, nose up */ Elevator [3]uint16 /*Rudder Rudder setpoints: nose left, center, nose right */ Rudder [3]uint16 /*Gyro Tail gyro mode/gain setpoints: heading hold, rate mode */ Gyro [2]uint16 /*Pitch Pitch curve setpoints (every 25%) */ Pitch [5]uint16 /*Throttle Throttle curve setpoints (every 25%) */ Throttle [5]uint16 /*HasExtensionFieldValues indicates if this message has any extensions and */ HasExtensionFieldValues bool }
RadioCalibration Complete set of calibration parameters for the radio
func (*RadioCalibration) GetDialect ¶
func (m *RadioCalibration) GetDialect() string
GetDialect gets the name of the dialect that defines the Message
func (*RadioCalibration) GetID ¶
func (m *RadioCalibration) GetID() uint32
GetID gets the ID of the Message
func (*RadioCalibration) GetMessageName ¶
func (m *RadioCalibration) GetMessageName() string
GetMessageName gets the name of the Message
func (*RadioCalibration) GetVersion ¶
func (m *RadioCalibration) GetVersion() int
GetVersion gets the MAVLink version of the Message contents
func (*RadioCalibration) HasExtensionFields ¶
func (m *RadioCalibration) HasExtensionFields() bool
HasExtensionFields returns true if the message definition contained extensions; false otherwise
func (*RadioCalibration) Read ¶
func (m *RadioCalibration) Read(frame mavlink2.Frame) (err error)
Read sets the field values of the message from the raw message payload
func (*RadioCalibration) String ¶
func (m *RadioCalibration) String() string
type UalbertaSysStatus ¶
type UalbertaSysStatus struct { /*Mode System mode, see UALBERTA_AUTOPILOT_MODE ENUM */ Mode uint8 /*NAVMode Navigation mode, see UALBERTA_NAV_MODE ENUM */ NAVMode uint8 /*Pilot Pilot mode, see UALBERTA_PILOT_MODE */ Pilot uint8 /*HasExtensionFieldValues indicates if this message has any extensions and */ HasExtensionFieldValues bool }
UalbertaSysStatus System status specific to ualberta uav
func (*UalbertaSysStatus) GetDialect ¶
func (m *UalbertaSysStatus) GetDialect() string
GetDialect gets the name of the dialect that defines the Message
func (*UalbertaSysStatus) GetID ¶
func (m *UalbertaSysStatus) GetID() uint32
GetID gets the ID of the Message
func (*UalbertaSysStatus) GetMessageName ¶
func (m *UalbertaSysStatus) GetMessageName() string
GetMessageName gets the name of the Message
func (*UalbertaSysStatus) GetVersion ¶
func (m *UalbertaSysStatus) GetVersion() int
GetVersion gets the MAVLink version of the Message contents
func (*UalbertaSysStatus) HasExtensionFields ¶
func (m *UalbertaSysStatus) HasExtensionFields() bool
HasExtensionFields returns true if the message definition contained extensions; false otherwise
func (*UalbertaSysStatus) Read ¶
func (m *UalbertaSysStatus) Read(frame mavlink2.Frame) (err error)
Read sets the field values of the message from the raw message payload
func (*UalbertaSysStatus) String ¶
func (m *UalbertaSysStatus) String() string