-
Notifications
You must be signed in to change notification settings - Fork 36
/
endpoint_broadcast_test.go
115 lines (99 loc) · 2.55 KB
/
endpoint_broadcast_test.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
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
package gomavlib
import (
"net"
"testing"
"github.com/stretchr/testify/require"
"github.com/bluenviron/gomavlib/v3/pkg/dialect"
"github.com/bluenviron/gomavlib/v3/pkg/frame"
)
var _ endpointChannelSingle = (*endpointUDPBroadcast)(nil)
type readWriterFromFuncs struct {
readFunc func([]byte) (int, error)
writeFunc func([]byte) (int, error)
}
func (rw *readWriterFromFuncs) Read(p []byte) (int, error) {
return rw.readFunc(p)
}
func (rw *readWriterFromFuncs) Write(p []byte) (int, error) {
return rw.writeFunc(p)
}
func TestEndpointBroadcast(t *testing.T) {
node, err := NewNode(NodeConf{
Dialect: testDialect,
OutVersion: V2,
OutSystemID: 10,
Endpoints: []EndpointConf{EndpointUDPBroadcast{"127.255.255.255:5602", ":5601"}},
HeartbeatDisable: true,
})
require.NoError(t, err)
defer node.Close()
evt := <-node.Events()
require.Equal(t, &EventChannelOpen{
Channel: evt.(*EventChannelOpen).Channel,
}, evt)
pc, err := net.ListenPacket("udp4", ":5602")
require.NoError(t, err)
defer pc.Close()
dialectRW, err := dialect.NewReadWriter(testDialect)
require.NoError(t, err)
rw, err := frame.NewReadWriter(frame.ReadWriterConf{
ReadWriter: &readWriterFromFuncs{
readFunc: func(p []byte) (int, error) {
n, _, err2 := pc.ReadFrom(p)
return n, err2
},
writeFunc: func(p []byte) (int, error) {
return pc.WriteTo(p, &net.UDPAddr{
IP: net.ParseIP("127.255.255.255"),
Port: 5601,
})
},
},
DialectRW: dialectRW,
OutVersion: frame.V2,
OutSystemID: 11,
})
require.NoError(t, err)
for i := 0; i < 3; i++ { //nolint:dupl
msg := &MessageHeartbeat{
Type: 1,
Autopilot: 2,
BaseMode: 3,
CustomMode: 6,
SystemStatus: 4,
MavlinkVersion: 5,
}
err = rw.WriteMessage(msg)
require.NoError(t, err)
evt = <-node.Events()
require.Equal(t, &EventFrame{
Frame: &frame.V2Frame{
SequenceNumber: byte(i),
SystemID: 11,
ComponentID: 1,
Message: msg,
Checksum: evt.(*EventFrame).Frame.GetChecksum(),
},
Channel: evt.(*EventFrame).Channel,
}, evt)
msg = &MessageHeartbeat{
Type: 6,
Autopilot: 5,
BaseMode: 4,
CustomMode: 3,
SystemStatus: 2,
MavlinkVersion: 1,
}
err := node.WriteMessageAll(msg)
require.NoError(t, err)
fr, err := rw.Read()
require.NoError(t, err)
require.Equal(t, &frame.V2Frame{
SequenceNumber: byte(i),
SystemID: 10,
ComponentID: 1,
Message: msg,
Checksum: fr.GetChecksum(),
}, fr)
}
}