1
0
mirror of https://github.com/hybridgroup/gobot.git synced 2025-04-24 13:48:49 +08:00
Thomas Kohler 865e724af0
Build(v2): revert move to v2 subfolder (#932)
* revert move to v2 subfolder
* fix CI and adjust CHANGELOG
2023-05-29 19:23:28 +02:00

61 lines
1.3 KiB
Go

//go:build example
// +build example
//
// Do not build by default.
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"
)
func main() {
adaptor := mavlink.NewAdaptor("/dev/ttyACM0")
iris := mavlink.NewDriver(adaptor)
work := func() {
iris.Once(mavlink.PacketEvent, 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(mavlink.MessageEvent, 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()
}