hybridgroup.gobot/platforms/mavlink
deadprogram d1e35afdc9 core: Refactor Mavlink platform for new Adaptor/Driver creation signatures
Signed-off-by: deadprogram <ron@hybridgroup.com>
2016-09-25 21:44:40 +02:00
..
common Merge pull request #293 from dgryski/misspell 2016-07-15 08:34:00 -06:00
LICENSE misc: update all LICENSE files for current year 2016-08-27 13:12:47 +02:00
README.md core: Refactor Mavlink platform for new Adaptor/Driver creation signatures 2016-09-25 21:44:40 +02:00
doc.go core: Refactor Mavlink platform for new Adaptor/Driver creation signatures 2016-09-25 21:44:40 +02:00
mavlink_adaptor.go core: Refactor Mavlink platform for new Adaptor/Driver creation signatures 2016-09-25 21:44:40 +02:00
mavlink_adaptor_test.go core: Refactor Mavlink platform for new Adaptor/Driver creation signatures 2016-09-25 21:44:40 +02:00
mavlink_driver.go core: Refactor Mavlink platform for new Adaptor/Driver creation signatures 2016-09-25 21:44:40 +02:00
mavlink_driver_test.go core: Refactor Mavlink platform for new Adaptor/Driver creation signatures 2016-09-25 21:44:40 +02:00

README.md

Mavlink

For information on the MAVlink communication protocol click here.

How to Install

go get -d -u github.com/hybridgroup/gobot/... && go install github.com/hybridgroup/gobot/platforms/mavlink

How to Use

package main

import (
	"fmt"

	"github.com/hybridgroup/gobot"
	"github.com/hybridgroup/gobot/platforms/mavlink"
	common "github.com/hybridgroup/gobot/platforms/mavlink/common"
)

func main() {
	gbot := gobot.NewGobot()

	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,
	)

	gbot.AddRobot(robot)

	gbot.Start()
}