-
Notifications
You must be signed in to change notification settings - Fork 34
/
node_streamrequest.go
183 lines (156 loc) · 4.25 KB
/
node_streamrequest.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
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
package gomavlib
import (
"reflect"
"sync"
"time"
"github.com/bluenviron/gomavlib/v3/pkg/message"
)
const (
streamRequestPeriod = 30 * time.Second
)
type streamNode struct {
Channel *Channel
SystemID byte
ComponentID byte
}
type nodeStreamRequest struct {
n *Node
msgHeartbeat message.Message
msgRequestDataStream message.Message
lastRequestsMutex sync.Mutex
lastRequests map[streamNode]time.Time
// in
terminate chan struct{}
// out
done chan struct{}
}
func newNodeStreamRequest(n *Node) *nodeStreamRequest {
// module is disabled
if !n.conf.StreamRequestEnable {
return nil
}
// dialect must be enabled
if n.conf.Dialect == nil {
return nil
}
// heartbeat message must exist in dialect and correspond to standard
msgHeartbeat := func() message.Message {
for _, m := range n.conf.Dialect.Messages {
if m.GetID() == 0 {
return m
}
}
return nil
}()
if msgHeartbeat == nil {
return nil
}
mde, err := message.NewReadWriter(msgHeartbeat)
if err != nil || mde.CRCExtra() != 50 {
return nil
}
// request data stream message must exist in dialect and correspond to standard
msgRequestDataStream := func() message.Message {
for _, m := range n.conf.Dialect.Messages {
if m.GetID() == 66 {
return m
}
}
return nil
}()
if msgRequestDataStream == nil {
return nil
}
mde, err = message.NewReadWriter(msgRequestDataStream)
if err != nil || mde.CRCExtra() != 148 {
return nil
}
sr := &nodeStreamRequest{
n: n,
msgHeartbeat: msgHeartbeat,
msgRequestDataStream: msgRequestDataStream,
lastRequests: make(map[streamNode]time.Time),
terminate: make(chan struct{}),
done: make(chan struct{}),
}
return sr
}
func (sr *nodeStreamRequest) close() {
close(sr.terminate)
<-sr.done
}
func (sr *nodeStreamRequest) run() {
defer close(sr.done)
ticker := time.NewTicker(30 * time.Second)
defer ticker.Stop()
for {
select {
// periodic cleanup
case now := <-ticker.C:
func() {
sr.lastRequestsMutex.Lock()
defer sr.lastRequestsMutex.Unlock()
for rnode, t := range sr.lastRequests {
if now.Sub(t) >= streamRequestPeriod {
delete(sr.lastRequests, rnode)
}
}
}()
case <-sr.terminate:
return
}
}
}
func (sr *nodeStreamRequest) onEventFrame(evt *EventFrame) {
// message must be heartbeat and sender must be an ardupilot device
if evt.Message().GetID() != 0 ||
reflect.ValueOf(evt.Message()).Elem().FieldByName("Autopilot").Uint() != 3 {
return
}
rnode := streamNode{
Channel: evt.Channel,
SystemID: evt.SystemID(),
ComponentID: evt.ComponentID(),
}
// request streams if sender is new or a request has not been sent in some time
request := false
func() {
sr.lastRequestsMutex.Lock()
defer sr.lastRequestsMutex.Unlock()
now := time.Now()
if _, ok := sr.lastRequests[rnode]; !ok {
sr.lastRequests[rnode] = time.Now()
request = true
} else if now.Sub(sr.lastRequests[rnode]) >= streamRequestPeriod {
request = true
sr.lastRequests[rnode] = now
}
}()
if request {
// https://github.com/mavlink/qgroundcontrol/blob/08f400355a8f3acf1dd8ed91f7f1c757323ac182/src
// /FirmwarePlugin/APM/APMFirmwarePlugin.cc#L626
streams := []int{
1, // common.MAV_DATA_STREAM_RAW_SENSORS,
2, // common.MAV_DATA_STREAM_EXTENDED_STATUS,
3, // common.MAV_DATA_STREAM_RC_CHANNELS,
6, // common.MAV_DATA_STREAM_POSITION,
10, // common.MAV_DATA_STREAM_EXTRA1,
11, // common.MAV_DATA_STREAM_EXTRA2,
12, // common.MAV_DATA_STREAM_EXTRA3,
}
for _, stream := range streams {
m := reflect.New(reflect.TypeOf(sr.msgRequestDataStream).Elem())
m.Elem().FieldByName("TargetSystem").SetUint(uint64(evt.SystemID()))
m.Elem().FieldByName("TargetComponent").SetUint(uint64(evt.ComponentID()))
m.Elem().FieldByName("ReqStreamId").SetUint(uint64(stream))
m.Elem().FieldByName("ReqMessageRate").SetUint(uint64(sr.n.conf.StreamRequestFrequency))
m.Elem().FieldByName("StartStop").SetUint(uint64(1))
sr.n.WriteMessageTo(evt.Channel, m.Interface().(message.Message)) //nolint:errcheck
}
sr.n.pushEvent(&EventStreamRequested{
Channel: evt.Channel,
SystemID: evt.SystemID(),
ComponentID: evt.ComponentID(),
})
}
}