hybridgroup.gobot/platforms/mavlink
Joe Kim 515c4e8288 fix mavlink README to use correct example code 2019-05-22 11:34:39 +02:00
..
common mavlink: add a Mavlink-over-UDP adaptor. 2017-04-16 20:32:15 +02:00
LICENSE docs: update copyright date to 2018 2018-02-14 08:24:39 +01:00
README.md fix mavlink README to use correct example code 2019-05-22 11:34:39 +02:00
doc.go docs: correct Mavlink README link 2016-12-21 10:53:19 +01:00
mavlink_adaptor.go mavlink: switch to using go-serial package 2017-06-15 14:04:08 +02:00
mavlink_adaptor_test.go mavlink: increase test coverage 2017-04-06 10:52:59 +02:00
mavlink_driver.go mavlink: add a Mavlink-over-UDP adaptor. 2017-04-16 20:32:15 +02:00
mavlink_driver_test.go mavlink: increase test coverage 2017-04-06 10:52:59 +02:00
mavlink_udp_adaptor.go mavlink: create UDPConnection interface for testabilty 2017-04-19 09:25:43 +02:00
mavlink_udp_adaptor_test.go mavlink: increase test coverage 2017-04-19 09:25:43 +02:00

README.md

Mavlink

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 2018-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/...

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() {
		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()
}

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.