hybridgroup.gobot/platforms/mavlink/mavlink_driver_test.go

90 lines
2.1 KiB
Go
Raw Normal View History

//nolint:forcetypeassert,nilnil // ok here
2014-08-01 14:39:52 +08:00
package mavlink
import (
"io"
"strings"
2014-08-01 14:39:52 +08:00
"testing"
2014-12-18 08:31:49 +08:00
"time"
2014-08-01 14:39:52 +08:00
"github.com/stretchr/testify/assert"
"github.com/stretchr/testify/require"
"gobot.io/x/gobot/v2"
common "gobot.io/x/gobot/v2/platforms/mavlink/common"
2014-08-01 14:39:52 +08:00
)
var _ gobot.Driver = (*Driver)(nil)
func initTestMavlinkDriver() *Driver {
m := NewAdaptor("/dev/null")
m.connect = func(port string) (io.ReadWriteCloser, error) { return nil, nil }
2014-12-18 08:31:49 +08:00
m.sp = nullReadWriteCloser{}
return NewDriver(m)
2014-08-01 14:39:52 +08:00
}
2014-12-18 08:31:49 +08:00
func TestMavlinkDriver(t *testing.T) {
m := NewAdaptor("/dev/null")
2014-12-18 08:31:49 +08:00
m.sp = nullReadWriteCloser{}
m.connect = func(port string) (io.ReadWriteCloser, error) { return nil, nil }
2014-12-18 08:31:49 +08:00
d := NewDriver(m)
assert.NotNil(t, d.Connection())
assert.Equal(t, 10*time.Millisecond, d.interval)
2014-12-18 08:31:49 +08:00
d = NewDriver(m, 100*time.Millisecond)
assert.Equal(t, 100*time.Millisecond, d.interval)
2014-12-18 08:31:49 +08:00
}
func TestMavlinkDriverName(t *testing.T) {
d := initTestMavlinkDriver()
assert.True(t, strings.HasPrefix(d.Name(), "Mavlink"))
d.SetName("NewName")
assert.Equal(t, "NewName", d.Name())
}
2014-08-01 14:39:52 +08:00
func TestMavlinkDriverStart(t *testing.T) {
d := initTestMavlinkDriver()
err := make(chan error)
packet := make(chan *common.MAVLinkPacket)
message := make(chan common.MAVLinkMessage)
2014-12-18 08:31:49 +08:00
_ = d.On(PacketEvent, func(data interface{}) {
2014-12-18 08:31:49 +08:00
packet <- data.(*common.MAVLinkPacket)
})
_ = d.On(MessageEvent, func(data interface{}) {
2014-12-18 08:31:49 +08:00
message <- data.(common.MAVLinkMessage)
})
_ = d.On(ErrorIOEvent, func(data interface{}) {
err <- data.(error)
})
_ = d.On(ErrorMAVLinkEvent, func(data interface{}) {
2014-12-18 08:31:49 +08:00
err <- data.(error)
})
require.NoError(t, d.Start())
2014-12-18 08:31:49 +08:00
select {
case p := <-packet:
require.NoError(t, d.SendPacket(p))
2014-12-18 08:31:49 +08:00
case <-time.After(100 * time.Millisecond):
require.Fail(t, "packet was not emitted")
2014-12-18 08:31:49 +08:00
}
select {
case <-message:
case <-time.After(100 * time.Millisecond):
require.Fail(t, "message was not emitted")
2014-12-18 08:31:49 +08:00
}
select {
case <-err:
case <-time.After(100 * time.Millisecond):
require.Fail(t, "error was not emitted")
2014-12-18 08:31:49 +08:00
}
2014-08-01 14:39:52 +08:00
}
func TestMavlinkDriverHalt(t *testing.T) {
d := initTestMavlinkDriver()
require.NoError(t, d.Halt())
2014-08-01 14:39:52 +08:00
}