gobot.io/x/gobot@v1.16.0/platforms/mavlink/mavlink_driver.go (about) 1 package mavlink 2 3 import ( 4 "time" 5 6 "gobot.io/x/gobot" 7 common "gobot.io/x/gobot/platforms/mavlink/common" 8 ) 9 10 const ( 11 // PacketEvent event 12 PacketEvent = "packet" 13 // MessageEvent event 14 MessageEvent = "message" 15 // ErrorIOEEvent event 16 ErrorIOEvent = "errorIO" 17 // ErrorMAVLinkEvent event 18 ErrorMAVLinkEvent = "errorMAVLink" 19 ) 20 21 type Driver struct { 22 name string 23 connection gobot.Connection 24 interval time.Duration 25 gobot.Eventer 26 } 27 28 type MavlinkInterface interface { 29 } 30 31 // NewDriver creates a new mavlink driver. 32 // 33 // It add the following events: 34 // "packet" - triggered when a new packet is read 35 // "message" - triggered when a new valid message is processed 36 func NewDriver(a BaseAdaptor, v ...time.Duration) *Driver { 37 m := &Driver{ 38 name: "Mavlink", 39 connection: a, 40 Eventer: gobot.NewEventer(), 41 interval: 10 * time.Millisecond, 42 } 43 44 if len(v) > 0 { 45 m.interval = v[0] 46 } 47 48 m.AddEvent(PacketEvent) 49 m.AddEvent(MessageEvent) 50 m.AddEvent(ErrorIOEvent) 51 m.AddEvent(ErrorMAVLinkEvent) 52 53 return m 54 } 55 56 func (m *Driver) Connection() gobot.Connection { return m.connection } 57 func (m *Driver) Name() string { return m.name } 58 func (m *Driver) SetName(n string) { m.name = n } 59 60 // adaptor returns driver associated adaptor 61 func (m *Driver) adaptor() BaseAdaptor { 62 return m.Connection().(BaseAdaptor) 63 } 64 65 // Start begins process to read mavlink packets every m.Interval 66 // and process them 67 func (m *Driver) Start() error { 68 go func() { 69 for { 70 packet, err := m.adaptor().ReadMAVLinkPacket() 71 if err != nil { 72 m.Publish(ErrorIOEvent, err) 73 continue 74 } 75 m.Publish(PacketEvent, packet) 76 message, err := packet.MAVLinkMessage() 77 if err != nil { 78 m.Publish(ErrorMAVLinkEvent, err) 79 continue 80 } 81 m.Publish(MessageEvent, message) 82 time.Sleep(m.interval) 83 } 84 }() 85 return nil 86 } 87 88 // Halt returns true if device is halted successfully 89 func (m *Driver) Halt() (err error) { return } 90 91 // SendPacket sends a packet to mavlink device 92 func (m *Driver) SendPacket(packet *common.MAVLinkPacket) (err error) { 93 _, err = m.adaptor().Write(packet.Pack()) 94 return err 95 }