-
Notifications
You must be signed in to change notification settings - Fork 36
/
node_streamrequest_test.go
61 lines (53 loc) · 1.21 KB
/
node_streamrequest_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
package gomavlib
import (
"testing"
"time"
"github.com/stretchr/testify/require"
"github.com/bluenviron/gomavlib/v3/pkg/dialect"
"github.com/bluenviron/gomavlib/v3/pkg/message"
)
func TestNodeStreamRequest(t *testing.T) {
dialect := &dialect.Dialect{
Version: 3,
Messages: []message.Message{
&MessageHeartbeat{},
&MessageRequestDataStream{},
},
}
node1, err := NewNode(NodeConf{
Dialect: dialect,
OutVersion: V2,
OutSystemID: 10,
Endpoints: []EndpointConf{
EndpointUDPServer{"127.0.0.1:5600"},
},
HeartbeatDisable: true,
StreamRequestEnable: true,
})
require.NoError(t, err)
defer node1.Close()
go func() {
for range node1.Events() { //nolint:revive
}
}()
node2, err := NewNode(NodeConf{
Dialect: dialect,
OutVersion: V2,
OutSystemID: 11,
Endpoints: []EndpointConf{
EndpointUDPClient{"127.0.0.1:5600"},
},
HeartbeatDisable: false,
HeartbeatPeriod: 500 * time.Millisecond,
HeartbeatAutopilotType: 3, // MAV_AUTOPILOT_ARDUPILOTMEGA
})
require.NoError(t, err)
defer node2.Close()
for evt := range node2.Events() {
if ee, ok := evt.(*EventFrame); ok {
if _, ok = ee.Message().(*MessageRequestDataStream); ok {
return
}
}
}
}