-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathmessage_test.go
79 lines (74 loc) · 1.8 KB
/
message_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
package xsens_test
import (
"bufio"
"fmt"
"os"
"testing"
"go.einride.tech/xsens"
"gotest.tools/v3/assert"
is "gotest.tools/v3/assert/cmp"
)
func TestNewMessage_TestData(t *testing.T) {
for _, tt := range []struct {
inputFile string
}{
{inputFile: "testdata/1/output.bin"},
{inputFile: "testdata/2/output.bin"},
{inputFile: "testdata/3/output.bin"},
{inputFile: "testdata/4/output.bin"},
{inputFile: "testdata/5/output.bin"},
} {
tt := tt
t.Run(tt.inputFile, func(t *testing.T) {
f, err := os.Open(tt.inputFile)
assert.NilError(t, err)
defer func() {
assert.NilError(t, f.Close())
}()
sc := bufio.NewScanner(f)
sc.Split(xsens.ScanMessages)
for sc.Scan() {
msg := xsens.Message(sc.Bytes())
newMsg := xsens.NewMessage(msg.Identifier(), msg.Data())
assert.NilError(t, newMsg.Validate())
assert.DeepEqual(t, msg, newMsg)
}
assert.NilError(t, sc.Err())
})
}
}
func TestNewMessage(t *testing.T) {
for _, tt := range []struct {
actual xsens.Message
expected xsens.Message
}{
{
actual: xsens.NewMessage(xsens.MessageIdentifierGotoConfig, nil),
expected: xsens.Message{0xfa, 0xff, 0x30, 0x00, 0xd1},
},
{
actual: xsens.NewMessage(xsens.MessageIdentifierError, []byte{byte(xsens.ErrorCodeInvalidMessage)}),
expected: xsens.Message{0xfa, 0xff, 0x42, 0x01, 0x04, 0xba},
},
} {
tt := tt
t.Run(fmt.Sprintf("%v", tt.actual), func(t *testing.T) {
assert.DeepEqual(t, tt.expected, tt.actual)
t.Run("Validate", func(t *testing.T) {
assert.NilError(t, tt.actual.Validate())
})
})
}
}
func TestMessage_Validate_Error(t *testing.T) {
for _, tt := range []xsens.Message{
{},
{0x00},
{0x00, 0x01},
} {
tt := tt
t.Run(tt.String(), func(t *testing.T) {
assert.Assert(t, is.ErrorContains(tt.Validate(), ""))
})
}
}