Documentation ¶
Index ¶
- Constants
- Variables
- type Dialect
- type Dialects
- type Frame
- type FrameLogger
- type FrameParser
- type FrameStream
- func (s *FrameStream) Close()
- func (s *FrameStream) Closed() <-chan struct{}
- func (s *FrameStream) GetCloseErr() error
- func (s *FrameStream) Read() <-chan Frame
- func (s *FrameStream) ReadContext(ctx context.Context)
- func (s *FrameStream) Write() chan<- Frame
- func (s *FrameStream) WriteContext(ctx context.Context)
- type FrameV1
- func (frame FrameV1) Bytes() []byte
- func (frame FrameV1) GetChecksum() uint16
- func (frame FrameV1) GetChecksumInput() []byte
- func (frame FrameV1) GetMessageBytes() []byte
- func (frame FrameV1) GetMessageID() uint32
- func (frame FrameV1) GetMessageLength() uint
- func (frame FrameV1) GetMessageSequence() uint
- func (frame FrameV1) GetSenderComponentID() uint8
- func (frame FrameV1) GetSenderSystemID() uint8
- func (frame FrameV1) GetVersion() int
- func (frame FrameV1) String() string
- type FrameV2
- func (frame FrameV2) Bytes() []byte
- func (frame FrameV2) GetChecksum() uint16
- func (frame FrameV2) GetChecksumInput() []byte
- func (frame FrameV2) GetCompatibilityFlags() uint8
- func (frame FrameV2) GetIncompatibilityFlags() uint8
- func (frame FrameV2) GetMessageBytes() []byte
- func (frame FrameV2) GetMessageID() uint32
- func (frame FrameV2) GetMessageLength() uint
- func (frame FrameV2) GetMessageSequence() uint
- func (frame FrameV2) GetSenderComponentID() uint8
- func (frame FrameV2) GetSenderSystemID() uint8
- func (frame FrameV2) GetSignature() []byte
- func (frame FrameV2) GetVersion() int
- func (frame FrameV2) String() string
- type Message
- type MessageMeta
- type UnknownMessage
- func (m *UnknownMessage) GetDialect() string
- func (m *UnknownMessage) GetID() uint32
- func (m *UnknownMessage) GetMessageName() string
- func (m *UnknownMessage) GetVersion() int
- func (m *UnknownMessage) Read(frame Frame) (err error)
- func (m *UnknownMessage) String() string
- func (m *UnknownMessage) Write(version int) ([]byte, error)
- type X25CRC
Constants ¶
const CompatibilityFlagSignature = 0x01
CompatibilityFlagSignature is the flag indicating that a V2 Frame is signed
const V1StartByte = 0xfe
V1StartByte is the magic frame start indicator for a V1 MAVLink Frame
const V2StartByte = 0xfd
V2StartByte is the magic frame start indicator for a V2 MAVLink Frame
Variables ¶
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
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
var ErrFrameTooShort = fmt.Errorf("Not enough bytes in Frame")
ErrFrameTooShort indicates the Frame did not contain enough bytes to complete the requested operation
var ErrInvalidChecksum = fmt.Errorf("Invalid checksum")
ErrInvalidChecksum indicates that the Message checksum is invalid
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
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
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
var ErrUnknownMessage = fmt.Errorf("Unknown message")
ErrUnknownMessage indicates that the Message is not defined in one of the loaded Dialects
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)
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
var ErrUserClosed = errors.New("User closed")
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
var ErrWriteChannelClosed = errors.New("Write channel closed")
Functions ¶
This section is empty.
Types ¶
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 ¶
GetMessage decodes the message in the Frame
type Frame ¶
type Frame interface { GetVersion() int GetMessageLength() uint GetMessageSequence() uint GetSenderSystemID() uint8 GetSenderComponentID() uint8 GetMessageBytes() []byte GetMessageID() uint32 GetChecksum() uint16 GetChecksumInput() []byte Bytes() []byte }
Frame represents a MAVLink frame containing a MAVLink message
type FrameLogger ¶ added in v0.13.0
An interface for logging frames read from the stream and for logging frames written to the stream
type FrameParser ¶
FrameParser represents a function that takes a Frame as input and returns a Message
type FrameStream ¶
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) 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) WriteContext ¶
func (s *FrameStream) WriteContext(ctx context.Context)
type FrameV1 ¶
type FrameV1 []byte
FrameV1 represents a MAVLink V1 Frame
func (FrameV1) GetChecksum ¶
GetChecksum returns the checksum of the Frame contents
func (FrameV1) GetChecksumInput ¶
GetChecksumInput returns the contents of the Frame used to calculate the checksum
func (FrameV1) GetMessageBytes ¶
GetMessageBytes returns the message contained in the Frame as a byte array
func (FrameV1) GetMessageID ¶
GetMessageID returns the ID of the message contained in the Frame
func (FrameV1) GetMessageLength ¶
GetMessageLength returns the length of the message contained in the Frame
func (FrameV1) GetMessageSequence ¶
GetMessageSequence the sequence number of the message contained in the Frame
func (FrameV1) GetSenderComponentID ¶
GetSenderComponentID returns the ID of the component that sent the Frame
func (FrameV1) GetSenderSystemID ¶
GetSenderSystemID returns the ID of the system that sent the Frame
func (FrameV1) GetVersion ¶
GetVersion returns the version of the Frame
type FrameV2 ¶
type FrameV2 []byte
FrameV2 represents a MAVLink V1 Frame
func (FrameV2) GetChecksum ¶
GetChecksum returns the checksum of the Frame contents
func (FrameV2) GetChecksumInput ¶
GetChecksumInput returns the contents of the Frame used to calculate the checksum
func (FrameV2) GetCompatibilityFlags ¶
GetCompatibilityFlags returns the compatibility flags for the Frame
func (FrameV2) GetIncompatibilityFlags ¶
GetIncompatibilityFlags returns the incompatibility flags for the Frame
func (FrameV2) GetMessageBytes ¶
GetMessageBytes returns the message contained in the Frame as a byte array
func (FrameV2) GetMessageID ¶
GetMessageID returns the ID of the message contained in the Frame
func (FrameV2) GetMessageLength ¶
GetMessageLength returns the length of the message contained in the Frame
func (FrameV2) GetMessageSequence ¶
GetMessageSequence the sequence number of the message contained in the Frame
func (FrameV2) GetSenderComponentID ¶
GetSenderComponentID returns the ID of the component that sent the Frame
func (FrameV2) GetSenderSystemID ¶
GetSenderSystemID returns the ID of the system that sent the Frame
func (FrameV2) GetSignature ¶
GetSignature returns the V2 Signature of the frame, if it exists
func (FrameV2) GetVersion ¶
GetVersion returns the version of the Frame
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 ¶
MessageMeta stores metadata information about a MAVLink message
type UnknownMessage ¶
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
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 ¶
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.