gobot.io/x/gobot/v2@v2.1.0/platforms/mavlink/mavlink_driver.go (about) 1 package mavlink 2 3 import ( 4 "time" 5 6 "gobot.io/x/gobot/v2" 7 common "gobot.io/x/gobot/v2/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 // 35 // "packet" - triggered when a new packet is read 36 // "message" - triggered when a new valid message is processed 37 func NewDriver(a BaseAdaptor, v ...time.Duration) *Driver { 38 m := &Driver{ 39 name: "Mavlink", 40 connection: a, 41 Eventer: gobot.NewEventer(), 42 interval: 10 * time.Millisecond, 43 } 44 45 if len(v) > 0 { 46 m.interval = v[0] 47 } 48 49 m.AddEvent(PacketEvent) 50 m.AddEvent(MessageEvent) 51 m.AddEvent(ErrorIOEvent) 52 m.AddEvent(ErrorMAVLinkEvent) 53 54 return m 55 } 56 57 func (m *Driver) Connection() gobot.Connection { return m.connection } 58 func (m *Driver) Name() string { return m.name } 59 func (m *Driver) SetName(n string) { m.name = n } 60 61 // adaptor returns driver associated adaptor 62 func (m *Driver) adaptor() BaseAdaptor { 63 return m.Connection().(BaseAdaptor) 64 } 65 66 // Start begins process to read mavlink packets every m.Interval 67 // and process them 68 func (m *Driver) Start() error { 69 go func() { 70 for { 71 packet, err := m.adaptor().ReadMAVLinkPacket() 72 if err != nil { 73 m.Publish(ErrorIOEvent, err) 74 continue 75 } 76 m.Publish(PacketEvent, packet) 77 message, err := packet.MAVLinkMessage() 78 if err != nil { 79 m.Publish(ErrorMAVLinkEvent, err) 80 continue 81 } 82 m.Publish(MessageEvent, message) 83 time.Sleep(m.interval) 84 } 85 }() 86 return nil 87 } 88 89 // Halt returns true if device is halted successfully 90 func (m *Driver) Halt() (err error) { return } 91 92 // SendPacket sends a packet to mavlink device 93 func (m *Driver) SendPacket(packet *common.MAVLinkPacket) (err error) { 94 _, err = m.adaptor().Write(packet.Pack()) 95 return err 96 }