2014-08-01 14:39:52 +08:00
|
|
|
package mavlink
|
|
|
|
|
|
|
|
import (
|
|
|
|
"fmt"
|
2014-08-04 09:18:01 +08:00
|
|
|
"time"
|
2014-08-01 14:39:52 +08:00
|
|
|
|
|
|
|
"github.com/hybridgroup/gobot"
|
|
|
|
common "github.com/hybridgroup/gobot/platforms/mavlink/common"
|
|
|
|
)
|
|
|
|
|
|
|
|
type MavlinkDriver struct {
|
|
|
|
gobot.Driver
|
|
|
|
}
|
|
|
|
|
|
|
|
type MavlinkInterface interface {
|
|
|
|
}
|
|
|
|
|
|
|
|
func NewMavlinkDriver(a *MavlinkAdaptor, name string) *MavlinkDriver {
|
|
|
|
m := &MavlinkDriver{
|
|
|
|
Driver: *gobot.NewDriver(
|
|
|
|
name,
|
|
|
|
"mavlink.MavlinkDriver",
|
|
|
|
a,
|
|
|
|
),
|
|
|
|
}
|
|
|
|
|
|
|
|
m.AddEvent("packet")
|
|
|
|
m.AddEvent("message")
|
|
|
|
|
|
|
|
return m
|
|
|
|
}
|
|
|
|
|
|
|
|
func (m *MavlinkDriver) adaptor() *MavlinkAdaptor {
|
|
|
|
return m.Driver.Adaptor().(*MavlinkAdaptor)
|
|
|
|
}
|
|
|
|
|
|
|
|
func (m *MavlinkDriver) Start() bool {
|
2014-08-04 09:18:01 +08:00
|
|
|
go func() {
|
|
|
|
for {
|
|
|
|
packet, err := common.ReadMAVLinkPacket(m.adaptor().sp)
|
|
|
|
if err != nil {
|
|
|
|
fmt.Println(err)
|
|
|
|
continue
|
|
|
|
}
|
|
|
|
gobot.Publish(m.Event("packet"), packet)
|
|
|
|
message, err := packet.MAVLinkMessage()
|
|
|
|
if err != nil {
|
|
|
|
fmt.Println(err)
|
|
|
|
continue
|
|
|
|
}
|
|
|
|
gobot.Publish(m.Event("message"), message)
|
|
|
|
<-time.After(m.Interval())
|
2014-08-01 14:39:52 +08:00
|
|
|
}
|
2014-08-04 09:18:01 +08:00
|
|
|
}()
|
2014-08-01 14:39:52 +08:00
|
|
|
return true
|
|
|
|
}
|
|
|
|
|
|
|
|
func (m *MavlinkDriver) SendPacket(packet *common.MAVLinkPacket) {
|
|
|
|
m.adaptor().sp.Write(packet.Pack())
|
|
|
|
}
|
|
|
|
|
|
|
|
func (m *MavlinkDriver) Halt() bool { return true }
|