2014-11-29 07:34:42 +08:00
|
|
|
# Mavlink
|
2014-08-01 14:39:52 +08:00
|
|
|
|
2014-11-29 07:34:42 +08:00
|
|
|
For information on the MAVlink communication protocol click [here](http://qgroundcontrol.org/mavlink/start).
|
2014-08-01 14:39:52 +08:00
|
|
|
|
2014-11-29 07:34:42 +08:00
|
|
|
## How to Install
|
2014-08-01 14:39:52 +08:00
|
|
|
|
2014-11-29 07:34:42 +08:00
|
|
|
```
|
2015-07-09 07:03:20 +08:00
|
|
|
go get -d -u github.com/hybridgroup/gobot/... && go install github.com/hybridgroup/gobot/platforms/mavlink
|
2014-08-01 14:39:52 +08:00
|
|
|
|
2014-11-29 07:34:42 +08:00
|
|
|
```
|
|
|
|
|
|
|
|
## How to Use
|
2014-08-01 14:39:52 +08:00
|
|
|
|
|
|
|
```go
|
|
|
|
package main
|
|
|
|
|
|
|
|
import (
|
|
|
|
"fmt"
|
|
|
|
|
|
|
|
"github.com/hybridgroup/gobot"
|
|
|
|
"github.com/hybridgroup/gobot/platforms/mavlink"
|
|
|
|
common "github.com/hybridgroup/gobot/platforms/mavlink/common"
|
|
|
|
)
|
|
|
|
|
|
|
|
func main() {
|
2016-10-16 02:02:54 +08:00
|
|
|
gbot := gobot.NewMaster()
|
2014-08-01 14:39:52 +08:00
|
|
|
|
2016-09-26 03:44:40 +08:00
|
|
|
adaptor := mavlink.NewAdaptor("/dev/ttyACM0")
|
|
|
|
iris := mavlink.NewDriver(adaptor)
|
2014-08-01 14:39:52 +08:00
|
|
|
|
|
|
|
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()
|
|
|
|
}
|
|
|
|
```
|