Add mavlink docs
This commit is contained in:
parent
086fa1efd4
commit
8e1d9e3a1d
File diff suppressed because it is too large
Load Diff
|
@ -1,9 +1,9 @@
|
|||
package mavlink
|
||||
|
||||
/** @file
|
||||
* @brief MAVLink comm protocol built from common.xml
|
||||
* @see http://pixhawk.ethz.ch/software/mavlink
|
||||
*/
|
||||
//
|
||||
// MAVLink comm protocol built from common.xml
|
||||
// http://pixhawk.ethz.ch/software/mavlink
|
||||
//
|
||||
|
||||
import (
|
||||
"bytes"
|
||||
|
@ -12,14 +12,16 @@ import (
|
|||
"time"
|
||||
)
|
||||
|
||||
const MAVLINK_BIG_ENDIAN = 0
|
||||
const MAVLINK_LITTLE_ENDIAN = 1
|
||||
const MAVLINK_STX = 254
|
||||
const MAVLINK_ENDIAN = MAVLINK_LITTLE_ENDIAN
|
||||
const MAVLINK_ALIGNED_FIELDS = 1
|
||||
const MAVLINK_CRC_EXTRA = 1
|
||||
const X25_INIT_CRC = 0xffff
|
||||
const X25_VALIDATE_CRC = 0xf0b8
|
||||
const (
|
||||
MAVLINK_BIG_ENDIAN = 0
|
||||
MAVLINK_LITTLE_ENDIAN = 1
|
||||
MAVLINK_STX = 254
|
||||
MAVLINK_ENDIAN = MAVLINK_LITTLE_ENDIAN
|
||||
MAVLINK_ALIGNED_FIELDS = 1
|
||||
MAVLINK_CRC_EXTRA = 1
|
||||
X25_INIT_CRC = 0xffff
|
||||
X25_VALIDATE_CRC = 0xf0b8
|
||||
)
|
||||
|
||||
var sequence uint16 = 0
|
||||
|
||||
|
@ -28,6 +30,7 @@ func generateSequence() uint8 {
|
|||
return uint8(sequence)
|
||||
}
|
||||
|
||||
// The MAVLinkMessage interface is implemented by MAVLink messages
|
||||
type MAVLinkMessage interface {
|
||||
Id() uint8
|
||||
Len() uint8
|
||||
|
@ -36,6 +39,7 @@ type MAVLinkMessage interface {
|
|||
Decode([]byte)
|
||||
}
|
||||
|
||||
// A MAVLinkPacket represents a raw packet received from a micro air vehicle
|
||||
type MAVLinkPacket struct {
|
||||
Protocol uint8
|
||||
Length uint8
|
||||
|
@ -47,6 +51,8 @@ type MAVLinkPacket struct {
|
|||
Checksum uint16
|
||||
}
|
||||
|
||||
// ReadMAVLinkPacket reads an io.Reader for a new packet and returns a new MAVLink packet
|
||||
// or returns the error received by the io.Reader
|
||||
func ReadMAVLinkPacket(r io.Reader) (*MAVLinkPacket, error) {
|
||||
for {
|
||||
header, err := read(r, 1)
|
||||
|
@ -72,6 +78,7 @@ func ReadMAVLinkPacket(r io.Reader) (*MAVLinkPacket, error) {
|
|||
}
|
||||
}
|
||||
|
||||
// CraftMAVLinkPacket returns a new MAVLinkPacket from a MAVLinkMessage
|
||||
func CraftMAVLinkPacket(SystemID uint8, ComponentID uint8, Message MAVLinkMessage) *MAVLinkPacket {
|
||||
return NewMAVLinkPacket(
|
||||
0xFE,
|
||||
|
@ -84,6 +91,7 @@ func CraftMAVLinkPacket(SystemID uint8, ComponentID uint8, Message MAVLinkMessag
|
|||
)
|
||||
}
|
||||
|
||||
// NewMAVLinkPacket returns a new MAVLinkPacket
|
||||
func NewMAVLinkPacket(Protocol uint8, Length uint8, Sequence uint8, SystemID uint8, ComponentID uint8, MessageID uint8, Data []uint8) *MAVLinkPacket {
|
||||
m := &MAVLinkPacket{
|
||||
Protocol: Protocol,
|
||||
|
@ -98,10 +106,13 @@ func NewMAVLinkPacket(Protocol uint8, Length uint8, Sequence uint8, SystemID uin
|
|||
return m
|
||||
}
|
||||
|
||||
// MAVLinkMessage returns the decoded MAVLinkMessage from the MAVLinkPacket
|
||||
// or returns an error generated from the MAVLinkMessage
|
||||
func (m *MAVLinkPacket) MAVLinkMessage() (MAVLinkMessage, error) {
|
||||
return NewMAVLinkMessage(m.MessageID, m.Data)
|
||||
}
|
||||
|
||||
// Pack returns a packed byte array which represents the MAVLinkPacket
|
||||
func (m *MAVLinkPacket) Pack() []byte {
|
||||
data := new(bytes.Buffer)
|
||||
binary.Write(data, binary.LittleEndian, m.Protocol)
|
||||
|
@ -115,6 +126,7 @@ func (m *MAVLinkPacket) Pack() []byte {
|
|||
return data.Bytes()
|
||||
}
|
||||
|
||||
// Decode accepts a packed byte array and populates the fields of the MAVLinkPacket
|
||||
func (m *MAVLinkPacket) Decode(buf []byte) {
|
||||
m.Protocol = buf[0]
|
||||
m.Length = buf[1]
|
||||
|
@ -147,15 +159,15 @@ func read(r io.Reader, length int) ([]byte, error) {
|
|||
return buf, nil
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Accumulate the X.25 CRC by adding one char at a time.
|
||||
*
|
||||
* The checksum function adds the hash of one char at a time to the
|
||||
* 16 bit checksum (uint16).
|
||||
*
|
||||
* @param data to hash
|
||||
* @param crcAccum the already accumulated checksum
|
||||
**/
|
||||
//
|
||||
// Accumulate the X.25 CRC by adding one char at a time.
|
||||
//
|
||||
// The checksum function adds the hash of one char at a time to the
|
||||
// 16 bit checksum (uint16).
|
||||
//
|
||||
// data to hash
|
||||
// crcAccum the already accumulated checksum
|
||||
//
|
||||
func crcAccumulate(data uint8, crcAccum uint16) uint16 {
|
||||
/*Accumulate one byte of data into the CRC*/
|
||||
var tmp uint8
|
||||
|
@ -166,19 +178,18 @@ func crcAccumulate(data uint8, crcAccum uint16) uint16 {
|
|||
return crcAccum
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Initiliaze the buffer for the X.25 CRC
|
||||
*
|
||||
*/
|
||||
//
|
||||
// Initiliaze the buffer for the X.25 CRC
|
||||
//
|
||||
func crcInit() uint16 {
|
||||
return X25_INIT_CRC
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Calculates the X.25 checksum on a byte buffer
|
||||
*
|
||||
* @return the checksum over the buffer bytes
|
||||
**/
|
||||
//
|
||||
// Calculates the X.25 checksum on a byte buffer
|
||||
//
|
||||
// return the checksum over the buffer bytes
|
||||
//
|
||||
func crcCalculate(m *MAVLinkPacket) uint16 {
|
||||
crc := crcInit()
|
||||
|
||||
|
|
|
@ -1,11 +1,13 @@
|
|||
package mavlink
|
||||
|
||||
/** @file
|
||||
* @brief MAVLink comm protocol built from common.xml
|
||||
* @see http://pixhawk.ethz.ch/software/mavlink
|
||||
*/
|
||||
//
|
||||
// MAVLink comm protocol built from common.xml
|
||||
// http://pixhawk.ethz.ch/software/mavlink
|
||||
//
|
||||
|
||||
const MAVLINK_BUILD_DATE = "Thu Jul 31 22:19:34 2014"
|
||||
const MAVLINK_WIRE_PROTOCOL_VERSION = "1.0"
|
||||
const MAVLINK_MAX_DIALECT_PAYLOAD_SIZE = 255
|
||||
const MAVLINK_VERSION = 3
|
||||
const (
|
||||
MAVLINK_BUILD_DATE = "Fri Sep 26 19:23:02 2014"
|
||||
MAVLINK_WIRE_PROTOCOL_VERSION = "1.0"
|
||||
MAVLINK_MAX_DIALECT_PAYLOAD_SIZE = 255
|
||||
MAVLINK_VERSION = 3
|
||||
)
|
||||
|
|
Loading…
Reference in New Issue