hybridgroup.gobot/examples/mavlink.go

63 lines
1.4 KiB
Go
Raw Permalink Normal View History

//go:build example
// +build example
//
// Do not build by default.
2014-08-01 14:39:52 +08:00
package main
import (
"fmt"
"gobot.io/x/gobot/v2"
"gobot.io/x/gobot/v2/platforms/mavlink"
common "gobot.io/x/gobot/v2/platforms/mavlink/common"
2014-08-01 14:39:52 +08:00
)
func main() {
adaptor := mavlink.NewAdaptor("/dev/ttyACM0")
iris := mavlink.NewDriver(adaptor)
2014-08-01 14:39:52 +08:00
work := func() {
_ = iris.Once(mavlink.PacketEvent, func(data interface{}) {
2014-08-01 14:39:52 +08:00
packet := data.(*common.MAVLinkPacket)
dataStream := common.NewRequestDataStream(100,
packet.SystemID,
packet.ComponentID,
4,
1,
)
if err := iris.SendPacket(
common.CraftMAVLinkPacket(packet.SystemID, packet.ComponentID, dataStream)); err != nil {
fmt.Println(err)
}
2014-08-01 14:39:52 +08:00
})
_ = iris.On(mavlink.MessageEvent, func(data interface{}) {
2014-08-01 14:39:52 +08:00
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,
)
if err := robot.Start(); err != nil {
panic(err)
}
2014-08-01 14:39:52 +08:00
}