hybridgroup.gobot/platforms/mavlink/mavlink_driver.go

96 lines
2.1 KiB
Go
Raw Normal View History

2014-08-01 14:39:52 +08:00
package mavlink
import (
2014-08-04 09:18:01 +08:00
"time"
2014-08-01 14:39:52 +08:00
"gobot.io/x/gobot"
common "gobot.io/x/gobot/platforms/mavlink/common"
2014-08-01 14:39:52 +08:00
)
const (
// PacketEvent event
PacketEvent = "packet"
// MessageEvent event
MessageEvent = "message"
// ErrorIOEEvent event
ErrorIOEvent = "errorIO"
// ErrorMAVLinkEvent event
ErrorMAVLinkEvent = "errorMAVLink"
)
type Driver struct {
name string
connection gobot.Connection
interval time.Duration
gobot.Eventer
2014-08-01 14:39:52 +08:00
}
type MavlinkInterface interface {
}
// NewDriver creates a new mavlink driver.
//
// It add the following events:
// "packet" - triggered when a new packet is read
// "message" - triggered when a new valid message is processed
func NewDriver(a BaseAdaptor, v ...time.Duration) *Driver {
m := &Driver{
name: "Mavlink",
connection: a,
Eventer: gobot.NewEventer(),
interval: 10 * time.Millisecond,
2014-08-01 14:39:52 +08:00
}
if len(v) > 0 {
m.interval = v[0]
}
m.AddEvent(PacketEvent)
m.AddEvent(MessageEvent)
m.AddEvent(ErrorIOEvent)
m.AddEvent(ErrorMAVLinkEvent)
2014-08-01 14:39:52 +08:00
return m
}
func (m *Driver) Connection() gobot.Connection { return m.connection }
func (m *Driver) Name() string { return m.name }
func (m *Driver) SetName(n string) { m.name = n }
// adaptor returns driver associated adaptor
func (m *Driver) adaptor() BaseAdaptor {
return m.Connection().(BaseAdaptor)
2014-08-01 14:39:52 +08:00
}
// Start begins process to read mavlink packets every m.Interval
// and process them
func (m *Driver) Start() error {
2014-08-04 09:18:01 +08:00
go func() {
for {
packet, err := m.adaptor().ReadMAVLinkPacket()
2014-08-04 09:18:01 +08:00
if err != nil {
m.Publish(ErrorIOEvent, err)
2014-08-04 09:18:01 +08:00
continue
}
m.Publish(PacketEvent, packet)
2014-08-04 09:18:01 +08:00
message, err := packet.MAVLinkMessage()
if err != nil {
m.Publish(ErrorMAVLinkEvent, err)
2014-08-04 09:18:01 +08:00
continue
}
m.Publish(MessageEvent, message)
time.Sleep(m.interval)
2014-08-01 14:39:52 +08:00
}
2014-08-04 09:18:01 +08:00
}()
return nil
2014-08-01 14:39:52 +08:00
}
// Halt returns true if device is halted successfully
func (m *Driver) Halt() (err error) { return }
// SendPacket sends a packet to mavlink device
func (m *Driver) SendPacket(packet *common.MAVLinkPacket) (err error) {
_, err = m.adaptor().Write(packet.Pack())
2014-11-20 08:03:50 +08:00
return err
2014-08-01 14:39:52 +08:00
}