-
-
Notifications
You must be signed in to change notification settings - Fork 1k
/
mavlink_adaptor.go
65 lines (52 loc) · 1.39 KB
/
mavlink_adaptor.go
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
package mavlink
import (
"io"
"go.bug.st/serial"
"gobot.io/x/gobot/v2"
common "gobot.io/x/gobot/v2/platforms/mavlink/common"
)
// Adaptor is a Mavlink transport adaptor.
type BaseAdaptor interface {
gobot.Connection
io.Writer
ReadMAVLinkPacket() (*common.MAVLinkPacket, error)
}
// Adaptor is a Mavlink-over-serial adaptor.
type Adaptor struct {
name string
port string
sp io.ReadWriteCloser
connect func(string) (io.ReadWriteCloser, error)
}
// NewAdaptor creates a new mavlink adaptor with specified port
func NewAdaptor(port string) *Adaptor {
return &Adaptor{
name: "Mavlink",
port: port,
connect: func(port string) (io.ReadWriteCloser, error) {
return serial.Open(port, &serial.Mode{BaudRate: 57600})
},
}
}
func (m *Adaptor) Name() string { return m.name }
func (m *Adaptor) SetName(n string) { m.name = n }
func (m *Adaptor) Port() string { return m.port }
// Connect returns true if connection to device is successful
func (m *Adaptor) Connect() error {
sp, err := m.connect(m.Port())
if err != nil {
return err
}
m.sp = sp
return nil
}
// Finalize returns true if connection to devices is closed successfully
func (m *Adaptor) Finalize() error {
return m.sp.Close()
}
func (m *Adaptor) ReadMAVLinkPacket() (*common.MAVLinkPacket, error) {
return common.ReadMAVLinkPacket(m.sp)
}
func (m *Adaptor) Write(b []byte) (int, error) {
return m.sp.Write(b)
}