mavlink

package
v1.5.0 Latest Latest
Warning

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

Go to latest
Published: May 10, 2017 License: Apache-2.0, Apache-2.0 Imports: 6 Imported by: 0

README

For information on the MAVlink communication protocol click here.

This package supports Mavlink over serial (such as a SiK modem) and Mavlink over UDP (such as via mavproxy). Serial is useful for point to point links, and UDP is useful for where you have multiple simultaneous clients such as the robot and QGroundControl.

As at 2017-04, this package supports Mavlink 1.0 only. If the robot doesn't receiving data then check that the other devices are configured to send version 1.0 frames.

How to Install

go get -d -u gobot.io/x/gobot/... && go install gobot.io/x/gobot/platforms/mavlink

How to Use

package main

import (
	"fmt"

	"gobot.io/x/gobot"
	"gobot.io/x/gobot/platforms/mavlink"
	common "gobot.io/x/gobot/platforms/mavlink/common"
)

func main() {
	adaptor := mavlink.NewAdaptor("/dev/ttyACM0")
	iris := mavlink.NewDriver(adaptor)

	work := func() {
		gobot.Once(iris.Event("packet"), func(data interface{}) {
			packet := data.(*common.MAVLinkPacket)

			dataStream := common.NewRequestDataStream(100,
				packet.SystemID,
				packet.ComponentID,
				4,
				1,
			)
			iris.SendPacket(common.CraftMAVLinkPacket(packet.SystemID,
				packet.ComponentID,
				dataStream,
			))
		})

		gobot.On(iris.Event("message"), func(data interface{}) {
			if data.(common.MAVLinkMessage).Id() == 30 {
				message := data.(*common.Attitude)
				fmt.Println("Attitude")
				fmt.Println("TIME_BOOT_MS", message.TIME_BOOT_MS)
				fmt.Println("ROLL", message.ROLL)
				fmt.Println("PITCH", message.PITCH)
				fmt.Println("YAW", message.YAW)
				fmt.Println("ROLLSPEED", message.ROLLSPEED)
				fmt.Println("PITCHSPEED", message.PITCHSPEED)
				fmt.Println("YAWSPEED", message.YAWSPEED)
				fmt.Println("")
			}
		})
	}

	robot := gobot.NewRobot("mavBot",
		[]gobot.Connection{adaptor},
		[]gobot.Device{iris},
		work,
	)

	robot.Start()
}

How to use: UDP

	adaptor := mavlink.NewUDPAdaptor(":14550")

To test, install Mavproxy and set it up to listen on serial and repeat over UDP:

$ mavproxy.py --out=udpbcast:192.168.0.255:14550

Change the address to the broadcast address of your subnet.

Documentation

Overview

Package mavlink contains the Gobot adaptor and driver for the MAVlink Communication Protocol.

Installing:

go get gobot.io/x/gobot/platforms/mavlink

Example:

package main

import (
	"fmt"

	"gobot.io/x/gobot"
	"gobot.io/x/gobot/platforms/mavlink"
	common "gobot.io/x/gobot/platforms/mavlink/common"
)

func main() {
	adaptor := mavlink.NewAdaptor("/dev/ttyACM0")
	iris := mavlink.NewDriver(adaptor)

	work := func() {
		iris.Once(iris.Event("packet"), func(data interface{}) {
			packet := data.(*common.MAVLinkPacket)

			dataStream := common.NewRequestDataStream(100,
				packet.SystemID,
				packet.ComponentID,
				4,
				1,
			)
			iris.SendPacket(common.CraftMAVLinkPacket(packet.SystemID,
				packet.ComponentID,
				dataStream,
			))
		})

		iris.On(iris.Event("message"), func(data interface{}) {
			if data.(common.MAVLinkMessage).Id() == 30 {
				message := data.(*common.Attitude)
				fmt.Println("Attitude")
				fmt.Println("TIME_BOOT_MS", message.TIME_BOOT_MS)
				fmt.Println("ROLL", message.ROLL)
				fmt.Println("PITCH", message.PITCH)
				fmt.Println("YAW", message.YAW)
				fmt.Println("ROLLSPEED", message.ROLLSPEED)
				fmt.Println("PITCHSPEED", message.PITCHSPEED)
				fmt.Println("YAWSPEED", message.YAWSPEED)
				fmt.Println("")
			}
		})
	}

	robot := gobot.NewRobot("mavBot",
		[]gobot.Connection{adaptor},
		[]gobot.Device{iris},
		work,
	)

	robot.Start()
}

For further information refer to mavlink README: https://github.com/hybridgroup/gobot/blob/master/platforms/mavlink/README.md

Index

Constants

View Source
const (
	// PacketEvent event
	PacketEvent = "packet"
	// MessageEvent event
	MessageEvent = "message"
	// ErrorIOEEvent event
	ErrorIOEvent = "errorIO"
	// ErrorMAVLinkEvent event
	ErrorMAVLinkEvent = "errorMAVLink"
)

Variables

This section is empty.

Functions

This section is empty.

Types

type Adaptor

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

Adaptor is a Mavlink-over-serial adaptor.

func NewAdaptor

func NewAdaptor(port string) *Adaptor

NewAdaptor creates a new mavlink adaptor with specified port

func (*Adaptor) Connect

func (m *Adaptor) Connect() (err error)

Connect returns true if connection to device is successful

func (*Adaptor) Finalize

func (m *Adaptor) Finalize() (err error)

Finalize returns true if connection to devices is closed successfully

func (*Adaptor) Name

func (m *Adaptor) Name() string

func (*Adaptor) Port

func (m *Adaptor) Port() string

func (*Adaptor) ReadMAVLinkPacket added in v1.5.0

func (m *Adaptor) ReadMAVLinkPacket() (*common.MAVLinkPacket, error)

func (*Adaptor) SetName

func (m *Adaptor) SetName(n string)

func (*Adaptor) Write added in v1.5.0

func (m *Adaptor) Write(b []byte) (int, error)

type BaseAdaptor added in v1.5.0

type BaseAdaptor interface {
	gobot.Connection

	io.Writer
	ReadMAVLinkPacket() (*common.MAVLinkPacket, error)
}

Adaptor is a Mavlink transport adaptor.

type Driver

type Driver struct {
	gobot.Eventer
	// contains filtered or unexported fields
}

func NewDriver

func NewDriver(a BaseAdaptor, v ...time.Duration) *Driver

NewDriver creates a new mavlink driver.

It add the following events:

"packet" - triggered when a new packet is read
"message" - triggered when a new valid message is processed

func (*Driver) Connection

func (m *Driver) Connection() gobot.Connection

func (*Driver) Halt

func (m *Driver) Halt() (err error)

Halt returns true if device is halted successfully

func (*Driver) Name

func (m *Driver) Name() string

func (*Driver) SendPacket

func (m *Driver) SendPacket(packet *common.MAVLinkPacket) (err error)

SendPacket sends a packet to mavlink device

func (*Driver) SetName

func (m *Driver) SetName(n string)

func (*Driver) Start

func (m *Driver) Start() error

Start begins process to read mavlink packets every m.Interval and process them

type MavlinkInterface

type MavlinkInterface interface {
}

type UDPAdaptor added in v1.5.0

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

func NewUDPAdaptor added in v1.5.0

func NewUDPAdaptor(port string) *UDPAdaptor

NewAdaptor creates a new Mavlink-over-UDP adaptor with specified port.

func (*UDPAdaptor) Connect added in v1.5.0

func (m *UDPAdaptor) Connect() error

Connect returns true if connection to device is successful

func (*UDPAdaptor) Finalize added in v1.5.0

func (m *UDPAdaptor) Finalize() (err error)

Finalize returns true if connection to devices is closed successfully

func (*UDPAdaptor) Name added in v1.5.0

func (m *UDPAdaptor) Name() string

func (*UDPAdaptor) Port added in v1.5.0

func (m *UDPAdaptor) Port() string

func (*UDPAdaptor) ReadMAVLinkPacket added in v1.5.0

func (m *UDPAdaptor) ReadMAVLinkPacket() (*common.MAVLinkPacket, error)

func (*UDPAdaptor) SetName added in v1.5.0

func (m *UDPAdaptor) SetName(n string)

func (*UDPAdaptor) Write added in v1.5.0

func (m *UDPAdaptor) Write(b []byte) (int, error)

type UDPConnection added in v1.5.0

type UDPConnection interface {
	Close() error
	ReadFromUDP([]byte) (int, *net.UDPAddr, error)
	WriteTo([]byte, net.Addr) (int, error)
}

Directories

Path Synopsis

Jump to

Keyboard shortcuts

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