hybridgroup.gobot/platforms/mavlink
deadprogram 885c829a43 license: update license year to include 2017
Signed-off-by: deadprogram <ron@hybridgroup.com>
2017-01-02 22:25:17 +01:00
..
common core: Use time.Sleep unless waiting for a timeout in a select 2016-11-05 13:05:49 +01:00
LICENSE license: update license year to include 2017 2017-01-02 22:25:17 +01:00
README.md core: use canonical import domain of gobot.io for all code 2016-12-08 13:24:03 +01:00
doc.go docs: correct Mavlink README link 2016-12-21 10:53:19 +01:00
mavlink_adaptor.go core: update Mavlink platform to simply return error 2016-11-07 21:29:52 +01:00
mavlink_adaptor_test.go core: use canonical import domain of gobot.io for all code 2016-12-08 13:24:03 +01:00
mavlink_driver.go core: use canonical import domain of gobot.io for all code 2016-12-08 13:24:03 +01:00
mavlink_driver_test.go core: use canonical import domain of gobot.io for all code 2016-12-08 13:24:03 +01:00

README.md

Mavlink

For information on the MAVlink communication protocol click here.

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