core: update Mavlink platform to simply return error
Signed-off-by: deadprogram <ron@hybridgroup.com>
This commit is contained in:
parent
76b5227a2d
commit
f2917e71bf
|
@ -29,9 +29,9 @@ func (m *Adaptor) SetName(n string) { m.name = n }
|
|||
func (m *Adaptor) Port() string { return m.port }
|
||||
|
||||
// Connect returns true if connection to device is successful
|
||||
func (m *Adaptor) Connect() (errs []error) {
|
||||
if sp, err := m.connect(m.Port()); err != nil {
|
||||
return []error{err}
|
||||
func (m *Adaptor) Connect() (err error) {
|
||||
if sp, e := m.connect(m.Port()); e != nil {
|
||||
return e
|
||||
} else {
|
||||
m.sp = sp
|
||||
}
|
||||
|
@ -39,9 +39,7 @@ func (m *Adaptor) Connect() (errs []error) {
|
|||
}
|
||||
|
||||
// Finalize returns true if connection to devices is closed successfully
|
||||
func (m *Adaptor) Finalize() (errs []error) {
|
||||
if err := m.sp.Close(); err != nil {
|
||||
return []error{err}
|
||||
}
|
||||
func (m *Adaptor) Finalize() (err error) {
|
||||
err = m.sp.Close()
|
||||
return
|
||||
}
|
||||
|
|
|
@ -57,18 +57,18 @@ func TestMavlinkAdaptor(t *testing.T) {
|
|||
}
|
||||
func TestMavlinkAdaptorConnect(t *testing.T) {
|
||||
a := initTestMavlinkAdaptor()
|
||||
gobottest.Assert(t, len(a.Connect()), 0)
|
||||
gobottest.Assert(t, a.Connect(), nil)
|
||||
|
||||
a.connect = func(port string) (io.ReadWriteCloser, error) { return nil, errors.New("connect error") }
|
||||
gobottest.Assert(t, a.Connect()[0], errors.New("connect error"))
|
||||
gobottest.Assert(t, a.Connect(), errors.New("connect error"))
|
||||
}
|
||||
|
||||
func TestMavlinkAdaptorFinalize(t *testing.T) {
|
||||
a := initTestMavlinkAdaptor()
|
||||
gobottest.Assert(t, len(a.Finalize()), 0)
|
||||
gobottest.Assert(t, a.Finalize(), nil)
|
||||
|
||||
testAdaptorClose = func() error {
|
||||
return errors.New("close error")
|
||||
}
|
||||
gobottest.Assert(t, a.Finalize()[0], errors.New("close error"))
|
||||
gobottest.Assert(t, a.Finalize(), errors.New("close error"))
|
||||
}
|
||||
|
|
|
@ -12,7 +12,7 @@ const (
|
|||
PacketEvent = "packet"
|
||||
// MessageEvent event
|
||||
MessageEvent = "message"
|
||||
// ErrorIOE event
|
||||
// ErrorIOEEvent event
|
||||
ErrorIOEvent = "errorIO"
|
||||
// ErrorMAVLinkEvent event
|
||||
ErrorMAVLinkEvent = "errorMAVLink"
|
||||
|
@ -64,7 +64,7 @@ func (m *Driver) adaptor() *Adaptor {
|
|||
|
||||
// Start begins process to read mavlink packets every m.Interval
|
||||
// and process them
|
||||
func (m *Driver) Start() (errs []error) {
|
||||
func (m *Driver) Start() error {
|
||||
go func() {
|
||||
for {
|
||||
packet, err := common.ReadMAVLinkPacket(m.adaptor().sp)
|
||||
|
@ -82,11 +82,11 @@ func (m *Driver) Start() (errs []error) {
|
|||
time.Sleep(m.interval)
|
||||
}
|
||||
}()
|
||||
return
|
||||
return nil
|
||||
}
|
||||
|
||||
// Halt returns true if device is halted successfully
|
||||
func (m *Driver) Halt() (errs []error) { return }
|
||||
func (m *Driver) Halt() (err error) { return }
|
||||
|
||||
// SendPacket sends a packet to mavlink device
|
||||
func (m *Driver) SendPacket(packet *common.MAVLinkPacket) (err error) {
|
||||
|
|
|
@ -51,7 +51,7 @@ func TestMavlinkDriverStart(t *testing.T) {
|
|||
err <- data.(error)
|
||||
})
|
||||
|
||||
gobottest.Assert(t, len(d.Start()), 0)
|
||||
gobottest.Assert(t, d.Start(), nil)
|
||||
|
||||
select {
|
||||
case p := <-packet:
|
||||
|
@ -74,5 +74,5 @@ func TestMavlinkDriverStart(t *testing.T) {
|
|||
|
||||
func TestMavlinkDriverHalt(t *testing.T) {
|
||||
d := initTestMavlinkDriver()
|
||||
gobottest.Assert(t, len(d.Halt()), 0)
|
||||
gobottest.Assert(t, d.Halt(), nil)
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue