mavlink2

package module
v0.13.0 Latest Latest
Warning

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

Go to latest
Published: Jan 29, 2021 License: MIT Imports: 9 Imported by: 0

README

go-mavlink2

MAVLink2 implementation in pure Go.

Documentation

Index

Constants

View Source
const CompatibilityFlagSignature = 0x01

CompatibilityFlagSignature is the flag indicating that a V2 Frame is signed

View Source
const V1StartByte = 0xfe

V1StartByte is the magic frame start indicator for a V1 MAVLink Frame

View Source
const V2StartByte = 0xfd

V2StartByte is the magic frame start indicator for a V2 MAVLink Frame

Variables

View Source
var ErrDecodeV2MessageV1Frame = fmt.Errorf("Unable to decode a V2 message from a V1 Frame")

ErrDecodeV2MessageV1Frame indicates that a request was made to decode a V2 Message from a V1 Frame

View Source
var ErrEncodeV2MessageV1Frame = fmt.Errorf("Unable to encode a V2 message to a V1 Frame")

ErrEncodeV2MessageV1Frame indicates that a request was made to encode a V2 Message for use with a V1 Frame

View Source
var ErrFrameTooShort = fmt.Errorf("Not enough bytes in Frame")

ErrFrameTooShort indicates the Frame did not contain enough bytes to complete the requested operation

View Source
var ErrInvalidChecksum = fmt.Errorf("Invalid checksum")

ErrInvalidChecksum indicates that the Message checksum is invalid

View Source
var ErrMessageTooLong = fmt.Errorf("Message too long")

ErrMessageTooLong indicates that the Message length in the header is longer than the maximum length allowed for the Message

View Source
var ErrMessageTooShort = fmt.Errorf("Message too short")

ErrMessageTooShort indicates that the Message length in the header is shorter than the minimum length allowed for the Message

View Source
var ErrPrivateField = fmt.Errorf("Struct contains one or more private fields that cannot be unmarshalled using binary.Read")

ErrPrivateField indicates that a Message contains private fields and cannot be unmarshalled using binary.Read

View Source
var ErrUnknownMessage = fmt.Errorf("Unknown message")

ErrUnknownMessage indicates that the Message is not defined in one of the loaded Dialects

View Source
var ErrUnknownStartByte = fmt.Errorf("Start byte is not 0x%x (V1) or 0x%x (V2)", V1StartByte, V2StartByte)

ErrUnknownStartByte indicates the Frame started with an unknown start byte (magic byte)

View Source
var ErrUnsupportedVersion = fmt.Errorf("The version requested is not supported by this library")

ErrUnsupportedVersion indicates that the version requested is not supported by this library

View Source
var ErrUserClosed = errors.New("User closed")
View Source
var ErrValueTooLong = fmt.Errorf("The input string was too long and was truncated")

ErrValueTooLong indicates that a Message field is unable to hold the requested string and that the string was truncated to fit

View Source
var ErrWriteChannelClosed = errors.New("Write channel closed")

Functions

This section is empty.

Types

type Dialect

type Dialect interface {
	GetMeta(uint32) (MessageMeta, error)
	GetMessage(Frame) (Message, error)
}

Dialect represents a collection of MAVLink message definitions

type Dialects

type Dialects []Dialect

Dialects represents a collection of Dialects

func (Dialects) GetFrame

func (d Dialects) GetFrame(version int, senderSystemID, senderComponentID, messageSequence uint8, message Message) (frame Frame, err error)

GetFrame builds a MAVLink frame containing the Message

func (Dialects) GetMessage

func (d Dialects) GetMessage(frame Frame) (message Message, err error)

GetMessage decodes the message in the Frame

func (Dialects) Validate

func (d Dialects) Validate(frame Frame) error

Validate checks the frame to see if there are any obvious errors

type Frame

type Frame interface {
	GetVersion() int
	GetMessageLength() uint8
	GetMessageSequence() uint8
	GetSenderSystemID() uint8
	GetSenderComponentID() uint8
	GetMessageBytes() []byte
	GetMessageID() uint32
	GetChecksum() uint16
	GetChecksumInput() []byte
	Bytes() []byte
}

Frame represents a MAVLink frame containing a MAVLink message

func FrameFromBytes

func FrameFromBytes(raw []byte, frameLength uint16, makeCopy bool) (frame Frame, err error)

FrameFromBytes returns a Frame containing the input bytes, or an error if the first byte is not a valid frame start

type FrameLogger added in v0.13.0

type FrameLogger interface {
	LogRead(msg []byte) error
	LogWritten(msg []byte) error
}

An interface for logging frames read from the stream and for logging frames written to the stream

type FrameParser

type FrameParser func(Frame) (Message, error)

FrameParser represents a function that takes a Frame as input and returns a Message

type FrameStream

type FrameStream struct {
	sync.RWMutex
	// contains filtered or unexported fields
}

FrameStream represents a stream of MAVLink Frames

func NewFrameStream

func NewFrameStream(rwc io.ReadWriteCloser, inputFrames chan Frame, dialects Dialects, returnInvalidFrames bool) *FrameStream

func NewFrameStreamWithLogger added in v0.13.0

func NewFrameStreamWithLogger(rwc io.ReadWriteCloser, inputFrames chan Frame, dialects Dialects, returnInvalidFrames bool, logger FrameLogger) *FrameStream

func (*FrameStream) Close

func (s *FrameStream) Close()

Close closes the FrameStream

func (*FrameStream) Closed

func (s *FrameStream) Closed() <-chan struct{}

Closed returns a channel that is closed when the FrameStream is closed

func (*FrameStream) GetCloseErr added in v0.13.0

func (s *FrameStream) GetCloseErr() error

func (*FrameStream) Read

func (s *FrameStream) Read() <-chan Frame

func (*FrameStream) ReadContext

func (s *FrameStream) ReadContext(ctx context.Context)

func (*FrameStream) Write

func (s *FrameStream) Write() chan<- Frame

Write returns a

func (*FrameStream) WriteContext

func (s *FrameStream) WriteContext(ctx context.Context)

type FrameV1

type FrameV1 []byte

FrameV1 represents a MAVLink V1 Frame

func (FrameV1) Bytes

func (frame FrameV1) Bytes() []byte

Bytes returns the Frame as a byte array

func (FrameV1) GetChecksum

func (frame FrameV1) GetChecksum() uint16

GetChecksum returns the checksum of the Frame contents

func (FrameV1) GetChecksumInput

func (frame FrameV1) GetChecksumInput() []byte

GetChecksumInput returns the contents of the Frame used to calculate the checksum

func (FrameV1) GetMessageBytes

func (frame FrameV1) GetMessageBytes() []byte

GetMessageBytes returns the message contained in the Frame as a byte array

func (FrameV1) GetMessageID

func (frame FrameV1) GetMessageID() uint32

GetMessageID returns the ID of the message contained in the Frame

func (FrameV1) GetMessageLength

func (frame FrameV1) GetMessageLength() uint8

GetMessageLength returns the length of the message contained in the Frame

func (FrameV1) GetMessageSequence

func (frame FrameV1) GetMessageSequence() uint8

GetMessageSequence the sequence number of the message contained in the Frame

func (FrameV1) GetSenderComponentID

func (frame FrameV1) GetSenderComponentID() uint8

GetSenderComponentID returns the ID of the component that sent the Frame

func (FrameV1) GetSenderSystemID

func (frame FrameV1) GetSenderSystemID() uint8

GetSenderSystemID returns the ID of the system that sent the Frame

func (FrameV1) GetVersion

func (frame FrameV1) GetVersion() int

GetVersion returns the version of the Frame

func (FrameV1) String

func (frame FrameV1) String() string

type FrameV2

type FrameV2 []byte

FrameV2 represents a MAVLink V1 Frame

func (FrameV2) Bytes

func (frame FrameV2) Bytes() []byte

GetBytes returns the Frame as a byte array

func (FrameV2) GetChecksum

func (frame FrameV2) GetChecksum() uint16

GetChecksum returns the checksum of the Frame contents

func (FrameV2) GetChecksumInput

func (frame FrameV2) GetChecksumInput() []byte

GetChecksumInput returns the contents of the Frame used to calculate the checksum

func (FrameV2) GetCompatibilityFlags

func (frame FrameV2) GetCompatibilityFlags() uint8

GetCompatibilityFlags returns the compatibility flags for the Frame

func (FrameV2) GetIncompatibilityFlags

func (frame FrameV2) GetIncompatibilityFlags() uint8

GetIncompatibilityFlags returns the incompatibility flags for the Frame

func (FrameV2) GetMessageBytes

func (frame FrameV2) GetMessageBytes() []byte

GetMessageBytes returns the message contained in the Frame as a byte array

func (FrameV2) GetMessageID

func (frame FrameV2) GetMessageID() uint32

GetMessageID returns the ID of the message contained in the Frame

func (FrameV2) GetMessageLength

func (frame FrameV2) GetMessageLength() uint8

GetMessageLength returns the length of the message contained in the Frame

func (FrameV2) GetMessageSequence

func (frame FrameV2) GetMessageSequence() uint8

GetMessageSequence the sequence number of the message contained in the Frame

func (FrameV2) GetSenderComponentID

func (frame FrameV2) GetSenderComponentID() uint8

GetSenderComponentID returns the ID of the component that sent the Frame

func (FrameV2) GetSenderSystemID

func (frame FrameV2) GetSenderSystemID() uint8

GetSenderSystemID returns the ID of the system that sent the Frame

func (FrameV2) GetSignature

func (frame FrameV2) GetSignature() []byte

GetSignature returns the V2 Signature of the frame, if it exists

func (FrameV2) GetVersion

func (frame FrameV2) GetVersion() int

GetVersion returns the version of the Frame

func (FrameV2) String

func (frame FrameV2) String() string

type Message

type Message interface {
	GetVersion() int
	GetDialect() string
	GetMessageName() string
	GetID() uint32
	Read(Frame) error
	Write(int) ([]byte, error)
}

Message defines a common interface for MAVLink messages

type MessageMeta

type MessageMeta struct {
	CRCExtra      byte
	MinimumLength uint8
	MaximumLength uint8
}

MessageMeta stores metadata information about a MAVLink message

type UnknownMessage

type UnknownMessage struct {
	ID      uint32
	Version int
	Raw     []byte
}

UnknownMessage represents a message that is not part of any loaded Dialect

func (*UnknownMessage) GetDialect

func (m *UnknownMessage) GetDialect() string

GetDialect gets the name of the dialect that defines the Message

func (*UnknownMessage) GetID

func (m *UnknownMessage) GetID() uint32

GetID gets the ID of the Message

func (*UnknownMessage) GetMessageName

func (m *UnknownMessage) GetMessageName() string

GetMessageName gets the name of the Message

func (*UnknownMessage) GetVersion

func (m *UnknownMessage) GetVersion() int

GetVersion gets the MAVLink version of the Message contents

func (*UnknownMessage) Read

func (m *UnknownMessage) Read(frame Frame) (err error)

func (*UnknownMessage) String

func (m *UnknownMessage) String() string

func (*UnknownMessage) Write

func (m *UnknownMessage) Write(version int) ([]byte, error)

type X25CRC

type X25CRC struct {
	// contains filtered or unexported fields
}

X25CRC represents a 2-byte CRC redundancy check used to check MAVLink frame integrity

func (*X25CRC) BlockSize

func (hash *X25CRC) BlockSize() int

BlockSize returns the hash's underlying block size. The Write method must be able to accept any amount of data, but it may operate more efficiently if all writes are a multiple of the block size.

func (*X25CRC) Reset

func (hash *X25CRC) Reset()

Reset resets the Hash to its initial state.

func (*X25CRC) Size

func (hash *X25CRC) Size() int

Size returns the number of bytes Sum will return.

func (*X25CRC) Sum

func (hash *X25CRC) Sum(b []byte) []byte

Sum appends the current hash to b and returns the resulting slice. It does not change the underlying hash state.

func (*X25CRC) Write

func (hash *X25CRC) Write(input []byte) (int, error)

Directories

Path Synopsis

Jump to

Keyboard shortcuts

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