diff --git a/.golangci.yml b/.golangci.yml index 48a00cc4c..215dd56a9 100644 --- a/.golangci.yml +++ b/.golangci.yml @@ -32,15 +32,6 @@ linters: # Enable specific linter # https://golangci-lint.run/usage/linters/#enabled-by-default # note: typecheck can not be disabled, it is used to check code compilation - # - # TODO: this default linters needs to be disabled to run successfully, we have to fix - # all issues step by step to enable at least the default linters - disable: - - errcheck - - ineffassign - #- staticcheck - - unused - enable: - nolintlint diff --git a/api/api.go b/api/api.go index 4efeda1be..365d59e8f 100644 --- a/api/api.go +++ b/api/api.go @@ -38,11 +38,15 @@ func NewAPI(m *gobot.Master) *API { go func() { if a.Cert != "" && a.Key != "" { - http.ListenAndServeTLS(a.Host+":"+a.Port, a.Cert, a.Key, nil) + if err := http.ListenAndServeTLS(a.Host+":"+a.Port, a.Cert, a.Key, nil); err != nil { + panic(err) + } } else { log.Println("WARNING: API using insecure connection. " + "We recommend using an SSL certificate with Gobot.") - http.ListenAndServe(a.Host+":"+a.Port, nil) + if err := http.ListenAndServe(a.Host+":"+a.Port, nil); err != nil { + panic(err) + } } }() }, @@ -177,7 +181,9 @@ func (a *API) robeaux(res http.ResponseWriter, req *http.Request) { } else if t[len(t)-1] == "html" { res.Header().Set("Content-Type", "text/html; charset=utf-8") } - res.Write(buf) + if _, err := res.Write(buf); err != nil { + panic(err) + } } // mcp returns MCP route handler. @@ -261,10 +267,12 @@ func (a *API) robotDeviceEvent(res http.ResponseWriter, req *http.Request) { if event := a.master.Robot(req.URL.Query().Get(":robot")). Device(req.URL.Query().Get(":device")).(gobot.Eventer). Event(req.URL.Query().Get(":event")); len(event) > 0 { - device.(gobot.Eventer).On(event, func(data interface{}) { + if err := device.(gobot.Eventer).On(event, func(data interface{}) { d, _ := json.Marshal(data) dataChan <- string(d) - }) + }); err != nil { + panic(err) + } for { select { @@ -363,7 +371,9 @@ func (a *API) executeCommand(f func(map[string]interface{}) interface{}, ) { body := make(map[string]interface{}) - json.NewDecoder(req.Body).Decode(&body) + if err := json.NewDecoder(req.Body).Decode(&body); err != nil { + panic(err) + } if f != nil { a.writeJSON(map[string]interface{}{"result": f(body)}, res) @@ -376,7 +386,9 @@ func (a *API) executeCommand(f func(map[string]interface{}) interface{}, func (a *API) writeJSON(j interface{}, res http.ResponseWriter) { data, _ := json.Marshal(j) res.Header().Set("Content-Type", "application/json; charset=utf-8") - res.Write(data) + if _, err := res.Write(data); err != nil { + panic(err) + } } // Debug add handler to api that prints each request diff --git a/api/api_test.go b/api/api_test.go index 2d1939474..e7d0ce404 100644 --- a/api/api_test.go +++ b/api/api_test.go @@ -91,7 +91,7 @@ func TestMcp(t *testing.T) { a.ServeHTTP(response, request) var body map[string]interface{} - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Refute(t, body["MCP"].(map[string]interface{})["robots"], nil) gobottest.Refute(t, body["MCP"].(map[string]interface{})["commands"], nil) } @@ -103,7 +103,7 @@ func TestMcpCommands(t *testing.T) { a.ServeHTTP(response, request) var body map[string]interface{} - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body["commands"], []interface{}{"TestFunction"}) } @@ -120,7 +120,7 @@ func TestExecuteMcpCommand(t *testing.T) { response := httptest.NewRecorder() a.ServeHTTP(response, request) - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body.(map[string]interface{})["result"], "hey Beep Boop") // unknown command @@ -132,7 +132,7 @@ func TestExecuteMcpCommand(t *testing.T) { response = httptest.NewRecorder() a.ServeHTTP(response, request) - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body.(map[string]interface{})["error"], "Unknown Command") } @@ -143,7 +143,7 @@ func TestRobots(t *testing.T) { a.ServeHTTP(response, request) var body map[string]interface{} - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, len(body["robots"].([]interface{})), 3) } @@ -156,14 +156,14 @@ func TestRobot(t *testing.T) { a.ServeHTTP(response, request) var body map[string]interface{} - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body["robot"].(map[string]interface{})["name"].(string), "Robot1") // unknown robot request, _ = http.NewRequest("GET", "/api/robots/UnknownRobot1", nil) a.ServeHTTP(response, request) - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body["error"], "No Robot found with the name UnknownRobot1") } @@ -176,14 +176,14 @@ func TestRobotDevices(t *testing.T) { a.ServeHTTP(response, request) var body map[string]interface{} - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, len(body["devices"].([]interface{})), 3) // unknown robot request, _ = http.NewRequest("GET", "/api/robots/UnknownRobot1/devices", nil) a.ServeHTTP(response, request) - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body["error"], "No Robot found with the name UnknownRobot1") } @@ -196,14 +196,14 @@ func TestRobotCommands(t *testing.T) { a.ServeHTTP(response, request) var body map[string]interface{} - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body["commands"], []interface{}{"robotTestFunction"}) // unknown robot request, _ = http.NewRequest("GET", "/api/robots/UnknownRobot1/commands", nil) a.ServeHTTP(response, request) - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body["error"], "No Robot found with the name UnknownRobot1") } @@ -219,7 +219,7 @@ func TestExecuteRobotCommand(t *testing.T) { response := httptest.NewRecorder() a.ServeHTTP(response, request) - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body.(map[string]interface{})["result"], "hey Robot1, Beep Boop") // unknown command @@ -231,7 +231,7 @@ func TestExecuteRobotCommand(t *testing.T) { response = httptest.NewRecorder() a.ServeHTTP(response, request) - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body.(map[string]interface{})["error"], "Unknown Command") // uknown robot @@ -242,7 +242,7 @@ func TestExecuteRobotCommand(t *testing.T) { request.Header.Add("Content-Type", "application/json") a.ServeHTTP(response, request) - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body.(map[string]interface{})["error"], "No Robot found with the name UnknownRobot1") } @@ -258,7 +258,7 @@ func TestRobotDevice(t *testing.T) { a.ServeHTTP(response, request) var body map[string]interface{} - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body["device"].(map[string]interface{})["name"].(string), "Device1") // unknown device @@ -266,7 +266,7 @@ func TestRobotDevice(t *testing.T) { "/api/robots/Robot1/devices/UnknownDevice1", nil) a.ServeHTTP(response, request) - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body["error"], "No Device found with the name UnknownDevice1") } @@ -282,7 +282,7 @@ func TestRobotDeviceCommands(t *testing.T) { a.ServeHTTP(response, request) var body map[string]interface{} - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, len(body["commands"].([]interface{})), 2) // unknown device @@ -291,7 +291,7 @@ func TestRobotDeviceCommands(t *testing.T) { nil, ) a.ServeHTTP(response, request) - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body["error"], "No Device found with the name UnknownDevice1") } @@ -308,7 +308,7 @@ func TestExecuteRobotDeviceCommand(t *testing.T) { response := httptest.NewRecorder() a.ServeHTTP(response, request) - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body.(map[string]interface{})["result"].(string), "hello human") // unknown command @@ -320,7 +320,7 @@ func TestExecuteRobotDeviceCommand(t *testing.T) { response = httptest.NewRecorder() a.ServeHTTP(response, request) - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body.(map[string]interface{})["error"], "Unknown Command") // unknown device @@ -331,7 +331,7 @@ func TestExecuteRobotDeviceCommand(t *testing.T) { request.Header.Add("Content-Type", "application/json") a.ServeHTTP(response, request) - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body.(map[string]interface{})["error"], "No Device found with the name UnknownDevice1") } @@ -345,14 +345,14 @@ func TestRobotConnections(t *testing.T) { a.ServeHTTP(response, request) var body map[string]interface{} - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, len(body["connections"].([]interface{})), 3) // unknown robot request, _ = http.NewRequest("GET", "/api/robots/UnknownRobot1/connections", nil) a.ServeHTTP(response, request) - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body["error"], "No Robot found with the name UnknownRobot1") } @@ -368,7 +368,7 @@ func TestRobotConnection(t *testing.T) { a.ServeHTTP(response, request) var body map[string]interface{} - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body["connection"].(map[string]interface{})["name"].(string), "Connection1") // unknown connection @@ -377,7 +377,7 @@ func TestRobotConnection(t *testing.T) { nil, ) a.ServeHTTP(response, request) - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body["error"], "No Connection found with the name UnknownConnection1") } @@ -426,7 +426,7 @@ func TestRobotDeviceEvent(t *testing.T) { response, _ := http.Get(server.URL + eventsURL + "UnknownEvent") var body map[string]interface{} - json.NewDecoder(response.Body).Decode(&body) + _ = json.NewDecoder(response.Body).Decode(&body) gobottest.Assert(t, body["error"], "No Event found with the name UnknownEvent") } diff --git a/drivers/aio/analog_sensor_driver_test.go b/drivers/aio/analog_sensor_driver_test.go index f5f747d5d..51371689c 100644 --- a/drivers/aio/analog_sensor_driver_test.go +++ b/drivers/aio/analog_sensor_driver_test.go @@ -97,12 +97,12 @@ func TestAnalogSensorDriverStart(t *testing.T) { d.SetScaler(func(input int) float64 { return float64(input * input) }) // expect data to be received - d.Once(d.Event(Data), func(data interface{}) { + _ = d.Once(d.Event(Data), func(data interface{}) { gobottest.Assert(t, data.(int), 100) sem <- true }) - d.Once(d.Event(Value), func(data interface{}) { + _ = d.Once(d.Event(Value), func(data interface{}) { gobottest.Assert(t, data.(float64), 10000.0) sem <- true }) @@ -122,7 +122,7 @@ func TestAnalogSensorDriverStart(t *testing.T) { } // expect error to be received - d.Once(d.Event(Error), func(data interface{}) { + _ = d.Once(d.Event(Error), func(data interface{}) { gobottest.Assert(t, data.(error).Error(), "read error") sem <- true }) @@ -140,11 +140,11 @@ func TestAnalogSensorDriverStart(t *testing.T) { } // send a halt message - d.Once(d.Event(Data), func(data interface{}) { + _ = d.Once(d.Event(Data), func(data interface{}) { sem <- true }) - d.Once(d.Event(Value), func(data interface{}) { + _ = d.Once(d.Event(Value), func(data interface{}) { sem <- true }) diff --git a/drivers/aio/grove_drivers.go b/drivers/aio/grove_drivers.go index 0d86ee6f1..df6c776dc 100644 --- a/drivers/aio/grove_drivers.go +++ b/drivers/aio/grove_drivers.go @@ -13,10 +13,12 @@ type GroveRotaryDriver struct { // 10 Milliseconds given an AnalogReader and pin. // // Optionally accepts: -// time.Duration: Interval at which the AnalogSensor is polled for new information +// +// time.Duration: Interval at which the AnalogSensor is polled for new information // // Adds the following API Commands: -// "Read" - See AnalogSensor.Read +// +// "Read" - See AnalogSensor.Read func NewGroveRotaryDriver(a AnalogReader, pin string, v ...time.Duration) *GroveRotaryDriver { return &GroveRotaryDriver{ AnalogSensorDriver: NewAnalogSensorDriver(a, pin, v...), @@ -33,10 +35,12 @@ type GroveLightSensorDriver struct { // 10 Milliseconds given an AnalogReader and pin. // // Optionally accepts: -// time.Duration: Interval at which the AnalogSensor is polled for new information +// +// time.Duration: Interval at which the AnalogSensor is polled for new information // // Adds the following API Commands: -// "Read" - See AnalogSensor.Read +// +// "Read" - See AnalogSensor.Read func NewGroveLightSensorDriver(a AnalogReader, pin string, v ...time.Duration) *GroveLightSensorDriver { return &GroveLightSensorDriver{ AnalogSensorDriver: NewAnalogSensorDriver(a, pin, v...), @@ -53,10 +57,12 @@ type GrovePiezoVibrationSensorDriver struct { // 10 Milliseconds given an AnalogReader and pin. // // Optionally accepts: -// time.Duration: Interval at which the AnalogSensor is polled for new information +// +// time.Duration: Interval at which the AnalogSensor is polled for new information // // Adds the following API Commands: -// "Read" - See AnalogSensor.Read +// +// "Read" - See AnalogSensor.Read func NewGrovePiezoVibrationSensorDriver(a AnalogReader, pin string, v ...time.Duration) *GrovePiezoVibrationSensorDriver { sensor := &GrovePiezoVibrationSensorDriver{ AnalogSensorDriver: NewAnalogSensorDriver(a, pin, v...), @@ -64,11 +70,13 @@ func NewGrovePiezoVibrationSensorDriver(a AnalogReader, pin string, v ...time.Du sensor.AddEvent(Vibration) - sensor.On(sensor.Event(Data), func(data interface{}) { + if err := sensor.On(sensor.Event(Data), func(data interface{}) { if data.(int) > 1000 { sensor.Publish(sensor.Event(Vibration), data) } - }) + }); err != nil { + panic(err) + } return sensor } @@ -83,10 +91,12 @@ type GroveSoundSensorDriver struct { // 10 Milliseconds given an AnalogReader and pin. // // Optionally accepts: -// time.Duration: Interval at which the AnalogSensor is polled for new information +// +// time.Duration: Interval at which the AnalogSensor is polled for new information // // Adds the following API Commands: -// "Read" - See AnalogSensor.Read +// +// "Read" - See AnalogSensor.Read func NewGroveSoundSensorDriver(a AnalogReader, pin string, v ...time.Duration) *GroveSoundSensorDriver { return &GroveSoundSensorDriver{ AnalogSensorDriver: NewAnalogSensorDriver(a, pin, v...), diff --git a/drivers/aio/grove_drivers_test.go b/drivers/aio/grove_drivers_test.go index 42511652c..a5395a3ed 100644 --- a/drivers/aio/grove_drivers_test.go +++ b/drivers/aio/grove_drivers_test.go @@ -57,10 +57,10 @@ func TestAnalogDriverHalt(t *testing.T) { }) // Start the driver and allow for multiple digital reads - driver.Start() + _ = driver.Start() time.Sleep(20 * time.Millisecond) - driver.Halt() + _ = driver.Halt() lastCallCount := atomic.LoadInt32(&callCount) // If driver was not halted, digital reads would still continue time.Sleep(20 * time.Millisecond) @@ -93,7 +93,7 @@ func TestDriverPublishesError(t *testing.T) { gobottest.Assert(t, driver.Start(), nil) // expect error - driver.Once(driver.Event(Error), func(data interface{}) { + _ = driver.Once(driver.Event(Error), func(data interface{}) { gobottest.Assert(t, data.(error).Error(), "read error") close(sem) }) @@ -105,7 +105,7 @@ func TestDriverPublishesError(t *testing.T) { } // Cleanup - driver.Halt() + _ = driver.Halt() } } diff --git a/drivers/aio/grove_temperature_sensor_driver_test.go b/drivers/aio/grove_temperature_sensor_driver_test.go index df3585f0b..d47f0fec1 100644 --- a/drivers/aio/grove_temperature_sensor_driver_test.go +++ b/drivers/aio/grove_temperature_sensor_driver_test.go @@ -62,7 +62,7 @@ func TestGroveTempSensorPublishesTemperatureInCelsius(t *testing.T) { val = 585 return }) - d.Once(d.Event(Value), func(data interface{}) { + _ = d.Once(d.Event(Value), func(data interface{}) { gobottest.Assert(t, fmt.Sprintf("%.2f", data.(float64)), "31.62") sem <- true }) diff --git a/drivers/aio/helpers_test.go b/drivers/aio/helpers_test.go index 9c0079376..70df8edba 100644 --- a/drivers/aio/helpers_test.go +++ b/drivers/aio/helpers_test.go @@ -2,13 +2,6 @@ package aio import "sync" -type aioTestBareAdaptor struct{} - -func (t *aioTestBareAdaptor) Connect() (err error) { return } -func (t *aioTestBareAdaptor) Finalize() (err error) { return } -func (t *aioTestBareAdaptor) Name() string { return "" } -func (t *aioTestBareAdaptor) SetName(n string) {} - type aioTestAdaptor struct { name string port string diff --git a/drivers/aio/temperature_sensor_driver_test.go b/drivers/aio/temperature_sensor_driver_test.go index afc003d41..b6012b7d3 100644 --- a/drivers/aio/temperature_sensor_driver_test.go +++ b/drivers/aio/temperature_sensor_driver_test.go @@ -100,7 +100,7 @@ func TestTempSensorPublishesTemperatureInCelsius(t *testing.T) { val = 585 return }) - d.Once(d.Event(Value), func(data interface{}) { + _ = d.Once(d.Event(Value), func(data interface{}) { gobottest.Assert(t, fmt.Sprintf("%.2f", data.(float64)), "31.62") sem <- true }) @@ -129,7 +129,7 @@ func TestTempSensorPublishesError(t *testing.T) { gobottest.Assert(t, d.Start(), nil) // expect error - d.Once(d.Event(Error), func(data interface{}) { + _ = d.Once(d.Event(Error), func(data interface{}) { gobottest.Assert(t, data.(error).Error(), "read error") sem <- true }) diff --git a/drivers/common/mfrc522/mfrc522_pcd.go b/drivers/common/mfrc522/mfrc522_pcd.go index 5f8746398..34ace2574 100644 --- a/drivers/common/mfrc522/mfrc522_pcd.go +++ b/drivers/common/mfrc522/mfrc522_pcd.go @@ -41,7 +41,8 @@ type MFRC522Common struct { // The device supports SPI, I2C and UART (not implemented yet at gobot system level). // // Params: -// c BusConnection - the bus connection to use with this driver +// +// c BusConnection - the bus connection to use with this driver func NewMFRC522Common() *MFRC522Common { d := &MFRC522Common{} return d @@ -67,7 +68,9 @@ func (d *MFRC522Common) Initialize(c busConnection) error { {regMode, modeRegTxWaitRFBit | modeRegPolMFinBit | modeRegCRCPreset6363}, } for _, init := range initSequence { - d.writeByteData(init[0], init[1]) + if err := d.writeByteData(init[0], init[1]); err != nil { + return err + } } if err := d.switchAntenna(true); err != nil { diff --git a/drivers/common/mfrc522/mfrc522_pcd_register.go b/drivers/common/mfrc522/mfrc522_pcd_register.go index 85dcb89e7..416f6ff3e 100644 --- a/drivers/common/mfrc522/mfrc522_pcd_register.go +++ b/drivers/common/mfrc522/mfrc522_pcd_register.go @@ -12,8 +12,8 @@ const ( commandRegCalcCRC = 0x03 // activates the CRC coprocessor or performs a self-test commandRegTransmit = 0x04 // transmits data from the FIFO buffer // 0x05, 0x06 not used - commandRegNoCmdChange = 0x07 // no command change, can be used to modify the Command register bits without - commandRegReceive = 0x08 // activates the receiver circuits + //commandRegNoCmdChange = 0x07 // no command change, can be used to modify the Command register bits without + //commandRegReceive = 0x08 // activates the receiver circuits // 0x09..0x0B not used commandRegTransceive = 0x0C // transmits data from FIFO buffer to antenna and automatically activates the receiver after transmission // 0x0D reserved @@ -44,8 +44,8 @@ const ( ) const ( - // ------------ unused commands -------------------- - regDivIEn = 0x03 // enable and disable the passing of interrupt requests to IRQ pin +// ------------ unused commands -------------------- +// regDivIEn = 0x03 // enable and disable the passing of interrupt requests to IRQ pin ) const ( @@ -57,10 +57,10 @@ const ( comIrqRegErrIRq1anyBit = 0x02 // bit 1: error bit in the Error register is set, if 1 // Status1 register’s LoAlert bit is set in opposition to the LoAlert bit, the LoAlertIRq bit stores this event and // can only be reset as indicated by the Set1 bit in this register - comIrqRegLoAlertIRqBit = 0x04 // bit 2: if 1, see above + //comIrqRegLoAlertIRqBit = 0x04 // bit 2: if 1, see above // the Status1 register’s HiAlert bit is set in opposition to the HiAlert bit, the HiAlertIRq bit stores this event // and can only be reset as indicated by the Set1 bit in this register - comIrqRegHiAlertIRqBit = 0x08 // bit 3: if 1, see above + //comIrqRegHiAlertIRqBit = 0x08 // bit 3: if 1, see above // If a command terminates, for example, when the Command register changes its value from any command to Idle command. // If an unknown command is started, the Command register Command[3:0] value changes to the idle state and the // IdleIRq bit is set. The microcontroller starting the Idle command does not set the IdleIRq bit. @@ -71,28 +71,28 @@ const ( comIrqRegTxIRqBit = 0x40 // bit 6: set to 1, immediately after the last bit of the transmitted data was sent out // 1: indicates that the marked bits in the register are set // 0: indicates that the marked bits in the register are cleared - comIrqRegSet1Bit = 0x80 // bit 7: see above + //comIrqRegSet1Bit = 0x80 // bit 7: see above ) const ( regDivIrq = 0x05 // diverse interrupt request bits // ------------ values -------------------- - divIrqRegReset = 0x00 // see table 31 of data sheet + //divIrqRegReset = 0x00 // see table 31 of data sheet //divIrqRegReserved01 = 0x03 divIrqRegCRCIRqBit = 0x04 // bit 2: the CalcCRC command is active and all data is processed //divIrqRegReservedBit3 = 0x08 // this interrupt is set when either a rising or falling signal edge is detected - divIrqRegMfinActIRqBit = 0x10 // bit 4: MFIN is active; see above + //divIrqRegMfinActIRqBit = 0x10 // bit 4: MFIN is active; see above //divIrqRegReserved56 = 0x60 // 1: indicates that the marked bits in the register are set // 0: indicates that the marked bits in the register are cleared - divIrqRegSet2Bit = 0x80 // bit 7: see above + //divIrqRegSet2Bit = 0x80 // bit 7: see above ) const ( regError = 0x06 // error bits showing the error status of the last command executed // ------------ values -------------------- - errorRegReset = 0x00 // see table 33 of data sheet + //errorRegReset = 0x00 // see table 33 of data sheet // set to logic 1 if the SOF is incorrect automatically cleared during receiver start-up phase bit is only valid for // 106 kBd; during the MFAuthent command, the ProtocolErr bit is set to logic 1 if the number of bytes received in one // data stream is incorrect @@ -118,32 +118,32 @@ const ( ) const ( - // ------------ unused commands -------------------- - regStatus1 = 0x07 // communication status bits +// ------------ unused commands -------------------- +// regStatus1 = 0x07 // communication status bits ) const ( regStatus2 = 0x08 // receiver and transmitter status bits // ------------ values -------------------- - status2RegReset = 0x00 // see table 37 of data sheet + //status2RegReset = 0x00 // see table 37 of data sheet // bit 0..2 shows the state of the transmitter and receiver state machines - status2RegModemStateIdle = 0x00 // idle - status2RegModemStateWait = 0x01 // wait for the BitFraming register’s StartSend bit + //status2RegModemStateIdle = 0x00 // idle + //status2RegModemStateWait = 0x01 // wait for the BitFraming register’s StartSend bit // the minimum time for TxWait is defined by the TxWait register - status2RegModemStateTxWait = 0x02 // wait until RF field is present if the TMode register’s TxWaitRF bit is set to logic 1 - status2RegModemStateTransmitting = 0x03 + //status2RegModemStateTxWait = 0x02 // wait until RF field is present if the TMode register’s TxWaitRF bit is set to logic 1 + //status2RegModemStateTransmitting = 0x03 // the minimum time for RxWait is defined by the RxWait register - status2RegModemStateRxWait = 0x04 // wait until RF field is present if the TMode register’s TxWaitRF bit is set to logic 1 - status2RegModemStateWaitForData = 0x05 - status2RegModemStateReceiving = 0x06 + //status2RegModemStateRxWait = 0x04 // wait until RF field is present if the TMode register’s TxWaitRF bit is set to logic 1 + //status2RegModemStateWaitForData = 0x05 + //status2RegModemStateReceiving = 0x06 // all data communication with the card is encrypted; can only be set to logic 1 by a successful execution of the // MFAuthent command; only valid in Read/Write mode for MIFARE standard cards; this bit is cleared by software status2RegMFCrypto1OnBit = 0x08 // bit 3: indicates that the MIFARE Crypto1 unit is switched on and, see above //status2RegReserved45 = 0x30 // 1: the I2C-bus input filter is set to the High-speed mode independent of the I2C-bus protocol // 0: the I2C-bus input filter is set to the I2C-bus protocol used - status2RegI2cForceHSBit = 0x40 // I2C-bus input filter settings, see above - status2RegTempSensClear1Bit = 0x80 // clears the temperature error if the temperature is below the alarm limit of 125C + //status2RegI2cForceHSBit = 0x40 // I2C-bus input filter settings, see above + //status2RegTempSensClear1Bit = 0x80 // clears the temperature error if the temperature is below the alarm limit of 125C ) const ( @@ -153,30 +153,30 @@ const ( const ( regFIFOLevel = 0x0A // number of bytes stored in the FIFO buffer // ------------ values -------------------- - fifoLevelRegReset = 0x00 // see table 41 of data sheet + //fifoLevelRegReset = 0x00 // see table 41 of data sheet // indicates the number of bytes stored in the FIFO buffer writing to the FIFOData register increments and reading // decrements the FIFOLevel value - fifoLevelRegValue = 0x7F // bit 0..6: see above + //fifoLevelRegValue = 0x7F // bit 0..6: see above // immediately clears the internal FIFO buffer’s read and write pointer and Error register’s BufferOvfl bit reading // this bit always returns 0 fifoLevelRegFlushBufferBit = 0x80 // bit 7: see above ) const ( - // ------------ unused commands -------------------- - regWaterLevel = 0x0B // level for FIFO underflow and overflow warning +// ------------ unused commands -------------------- +// regWaterLevel = 0x0B // level for FIFO underflow and overflow warning ) const ( regControl = 0x0C // miscellaneous control registers // ------------ values -------------------- - controlRegReset = 0x10 // see table 45 of data sheet + //controlRegReset = 0x10 // see table 45 of data sheet // indicates the number of valid bits in the last received byte // if this value is 000b, the whole byte is valid controlRegRxLastBits = 0x07 // bit 0..2: see above //controlRegReserved3to5 = 0x38 - controlRegTStartNowBit = 0x40 // bit 6: timer starts immediately, if 1; reading always returns logic 0 - controlRegTStopNow = 0x80 // bit 7: timer stops immediately, if 1; reading always returns logic 0 + //controlRegTStartNowBit = 0x40 // bit 6: timer starts immediately, if 1; reading always returns logic 0 + //controlRegTStopNow = 0x80 // bit 7: timer stops immediately, if 1; reading always returns logic 0 ) const ( @@ -194,7 +194,7 @@ const ( // 7: LSB of the received bit is stored at bit position 7, the second received bit is stored in the next byte that // follows at bit position 0 // These bits are only to be used for bitwise anticollision at 106 kBd, for all other modes they are set to 0 - bitFramingRegRxAlign = 0x70 // bit 4..6: see above + //bitFramingRegRxAlign = 0x70 // bit 4..6: see above //starts the transmission of data, only valid in combination with the Transceive command bitFramingRegStartSendBit = 0x80 // bit 7: see above ) @@ -207,9 +207,9 @@ const ( // 01: indicates a bit-collision in the 1st bit // 08: indicates a bit-collision in the 8th bit // These bits will only be interpreted if the CollPosNotValid bit is set to logic 0 - collRegCollPos = 0x1F // bit 0..4: read-only, see above + //collRegCollPos = 0x1F // bit 0..4: read-only, see above // no collision detected or the position of the collision is out of the range of CollPos[4:0], if set to 1 - collRegCollPosNotValidBit = 0x20 // bit 5: read-only, see above + //collRegCollPosNotValidBit = 0x20 // bit 5: read-only, see above //collRegReservedBit6 = 0x40 // all received bits will be cleared after a collision only used during bitwise anticollision at 106 kBd, otherwise it // is set to logic 1 @@ -223,7 +223,7 @@ const ( const ( regMode = 0x11 // defines general modes for transmitting and receiving // ------------ values -------------------- - modeRegReset = 0x3F // see table 55 of data sheet + //modeRegReset = 0x3F // see table 55 of data sheet // bit 0..1: defines the preset value for the CRC coprocessor for the CalcCRC command; Remark: during any // communication, the preset values are selected automatically according to the definition of bits in the rxModeReg // and TxMode registers @@ -240,7 +240,7 @@ const ( //modeRegReservedBit6 = 0x40 // CRC coprocessor calculates the CRC with MSB first 0 in the CRCResult register the values for the CRCResultMSB[7:0] // bits and the CRCResultLSB[7:0] bits are bit reversed; Remark: during RF communication this bit is ignored - modeRegMSBFirstBit = 0x80 // bit 7: see above, if set to 1 + //modeRegMSBFirstBit = 0x80 // bit 7: see above, if set to 1 ) const ( @@ -258,28 +258,28 @@ const ( // end of a received data stream which is a copy of the Error register value. For the version 2.0 the // CRC status is reflected in the signal CRCOk, which indicates the actual status of the CRC coprocessor. For the // version 1.0 the CRC status is reflected in the signal CRCErr. - rxModeRegRxMultipleBit = 0x04 - // an invalid received data stream (less than 4 bits received) will be ignored and the receiver remains active - rxModeRegRxNoErrBit = 0x08 // bit 3 - txModeRegInvModBit = 0x08 // bit 3: modulation of transmitted data is inverted, if 1 - // bit 4..6: defines the bit rate during data transmission; the handles transfer speeds up to 848 kBd - rxtxModeRegSpeed106kBd = 0x00 //106 kBd - rxtxModeRegSpeed212kBd = 0x10 //212 kBd - rxtxModeRegSpeed424kBd = 0x20 //424 kBd - rxtxModeRegSpeed848kBd = 0x30 //848 kBd - rxtxModeRegSpeedRes1 = 0x40 //reserved - rxtxModeRegSpeedRes2 = 0x50 //reserved - rxtxModeRegSpeedRes3 = 0x60 //reserved - rxtxModeRegSpeedRes4 = 0x70 //reserved - // RX: enables the CRC calculation during reception - // TX: enables CRC generation during data transmission - rxtxModeRegTxCRCEnBit = 0x80 // bit 7: can only be set to logic 0 at 106 kBd +// rxModeRegRxMultipleBit = 0x04 +// an invalid received data stream (less than 4 bits received) will be ignored and the receiver remains active +//rxModeRegRxNoErrBit = 0x08 // bit 3 +//txModeRegInvModBit = 0x08 // bit 3: modulation of transmitted data is inverted, if 1 +// bit 4..6: defines the bit rate during data transmission; the handles transfer speeds up to 848 kBd +//rxtxModeRegSpeed106kBd = 0x00 //106 kBd +//rxtxModeRegSpeed212kBd = 0x10 //212 kBd +//rxtxModeRegSpeed424kBd = 0x20 //424 kBd +//rxtxModeRegSpeed848kBd = 0x30 //848 kBd +//rxtxModeRegSpeedRes1 = 0x40 //reserved +//rxtxModeRegSpeedRes2 = 0x50 //reserved +//rxtxModeRegSpeedRes3 = 0x60 //reserved +//rxtxModeRegSpeedRes4 = 0x70 //reserved +// RX: enables the CRC calculation during reception +// TX: enables CRC generation during data transmission +//rxtxModeRegTxCRCEnBit = 0x80 // bit 7: can only be set to logic 0 at 106 kBd ) const ( regTxControl = 0x14 // controls the logical behavior of the antenna driver pins TX1 and TX2 // ------------ values -------------------- - regtxControlRegReset = 0x80 // see table 61 of data sheet + //regtxControlRegReset = 0x80 // see table 61 of data sheet // signal on pin TX1 delivers the 13.56 MHz energy carrier modulated by the transmission data txControlRegTx1RFEn1outputBit = 0x01 // bit 0: see above // signal on pin TX2 delivers the 13.56 MHz energy carrier modulated by the transmission data @@ -287,33 +287,33 @@ const ( //txControlRegReservedBit2 = 0x04 // signal on pin TX2 continuously delivers the unmodulated 13.56 MHz energy carrier0Tx2CW bit is enabled to modulate // the 13.56 MHz energy carrier - txControlRegTx2CW1outputBit = 0x08 // bit 3: see above - txControlRegInvTx1RFOffBit = 0x10 // bit 4: output signal on pin TX1 inverted if driver TX1 is disabled, if 1 - txControlRegInvTx2RFOffBit = 0x20 // bit 5: output signal on pin TX2 inverted if driver TX2 is disabled, if 1 - txControlRegInvTx1RFOnBit = 0x40 // bit 6: output signal on pin TX1 inverted if driver TX1 is enabled, if 1 - txControlRegInvTx2RFOnBit = 0x80 // bit 7: output signal on pin TX2 inverted if driver TX2 is enabled, if 1 + //txControlRegTx2CW1outputBit = 0x08 // bit 3: see above + //txControlRegInvTx1RFOffBit = 0x10 // bit 4: output signal on pin TX1 inverted if driver TX1 is disabled, if 1 + //txControlRegInvTx2RFOffBit = 0x20 // bit 5: output signal on pin TX2 inverted if driver TX2 is disabled, if 1 + //txControlRegInvTx1RFOnBit = 0x40 // bit 6: output signal on pin TX1 inverted if driver TX1 is enabled, if 1 + //txControlRegInvTx2RFOnBit = 0x80 // bit 7: output signal on pin TX2 inverted if driver TX2 is enabled, if 1 ) const ( regTxASK = 0x15 // controls the setting of the transmission modulation // ------------ values -------------------- - txASKRegReset = 0x00 // see table 63 of data sheet + //txASKRegReset = 0x00 // see table 63 of data sheet //txASKRegReserved = 0x3F // bit 0..5 txASKRegForce100ASKBit = 0x40 // bit 6: forces a 100 % ASK modulation independent of the ModGsP register //txASKRegReservedBit7 = 0x80 ) const ( - regTxSel = 0x16 // selects the internal sources for the antenna driver - regRxSel = 0x17 // selects internal receiver settings - regRxThreshold = 0x18 // selects thresholds for the bit decoder - regDemod = 0x19 // defines demodulator settings + //regTxSel = 0x16 // selects the internal sources for the antenna driver + //regRxSel = 0x17 // selects internal receiver settings + //regRxThreshold = 0x18 // selects thresholds for the bit decoder + //regDemod = 0x19 // defines demodulator settings // 0x1A // reserved for future use // 0x1B // reserved for future use - regMfTx = 0x1C // controls some MIFARE communication transmit parameters - regMfRx = 0x1D // controls some MIFARE communication receive parameters + //regMfTx = 0x1C // controls some MIFARE communication transmit parameters + //regMfRx = 0x1D // controls some MIFARE communication receive parameters // 0x1E // reserved for future use - regSerialSpeed = 0x1F // selects the speed of the serial UART interface + //regSerialSpeed = 0x1F // selects the speed of the serial UART interface // Page 2: Configuration // 0x20 // reserved for future use @@ -333,7 +333,7 @@ const ( const ( regRFCfg = 0x26 // configures the receiver gain // ------------ values -------------------- - rfcCfgRegReset = 0x48 // see table 97 of data sheet + //rfcCfgRegReset = 0x48 // see table 97 of data sheet //rfcCfgRegReserved03 = 0x07 // bit 4..6: defines the receiver’s signal voltage gain factor rfcCfgRegRxGain18dB = 0x00 @@ -348,18 +348,18 @@ const ( ) const ( - // ------------ unused commands -------------------- - regGsN = 0x27 // selects the conductance of the antenna driver pins TX1 and TX2 for modulation - regCWGsP = 0x28 // defines the conductance of the p-driver output during periods of no modulation - regModGsP = 0x29 // defines the conductance of the p-driver output during periods of modulation +// ------------ unused commands -------------------- +//regGsN = 0x27 // selects the conductance of the antenna driver pins TX1 and TX2 for modulation +//regCWGsP = 0x28 // defines the conductance of the p-driver output during periods of no modulation +//regModGsP = 0x29 // defines the conductance of the p-driver output during periods of modulation ) const ( regTMode = 0x2A // defines settings for the internal timer regTPrescaler = 0x2B // the lower 8 bits of the TPrescaler value. The 4 high bits are in tModeReg. // ------------ values -------------------- - tModeRegReset = 0x00 // see table 105 of data sheet - tPrescalerRegReset = 0x00 // see table 107 of data sheet + //tModeRegReset = 0x00 // see table 105 of data sheet + //tPrescalerRegReset = 0x00 // see table 107 of data sheet // timer starts automatically at the end of the transmission in all communication modes at all speeds; if the // RxMode register’s RxMultiple bit is not set, the timer stops immediately after receiving the 5th bit (1 start // bit, 4 data bits); if the RxMultiple bit is set to logic 1 the timer never stops, in which case the timer can be @@ -368,22 +368,22 @@ const ( // bit 6,5: indicates that the timer is not influenced by the protocol; internal timer is running in // gated mode; Remark: in gated mode, the Status1 register’s TRunning bit is logic 1 when the timer is enabled by // the TMode register’s TGated bits; this bit does not influence the gating signal - tModeRegTGatedNon = 0x00 // non-gated mode - tModeRegTGatedMFIN = 0x20 // gated by pin MFIN - tModeRegTGatedAUX1 = 0x40 // gated by pin AUX1 + //tModeRegTGatedNon = 0x00 // non-gated mode + //tModeRegTGatedMFIN = 0x20 // gated by pin MFIN + //tModeRegTGatedAUX1 = 0x40 // gated by pin AUX1 // 1: timer automatically restarts its count-down from the 16-bit timer reload value instead of counting down to zero // 0: timer decrements to 0 and the ComIrq register’s TimerIRq bit is set to logic 1 - tModeRegTAutoRestartBit = 0x10 // bit 4, see above + //tModeRegTAutoRestartBit = 0x10 // bit 4, see above // defines the higher 4 bits of the TPrescaler value; The following formula is used to calculate the timer // frequency if the Demod register’s TPrescalEven bit in Demot register’s set to logic 0: // ftimer = 13.56 MHz / (2*TPreScaler+1); TPreScaler = [tPrescalerRegHi:tPrescalerRegLo] // TPrescaler value on 12 bits) (Default TPrescalEven bit is logic 0) // The following formula is used to calculate the timer frequency if the Demod register’s TPrescalEven bit is set // to logic 1: ftimer = 13.56 MHz / (2*TPreScaler+2). - tModeRegtPrescalerRegValue25us = 0x0A9 // 169 => fRegtimer=40kHz, timer period of 25μs. - tModeRegtPrescalerRegValue38us = 0x0FF // 255 => fRegtimer=26kHz, timer period of 38μs. - tModeRegtPrescalerRegValue500us = 0xD3E // 3390 => fRegtimer= 2kHz, timer period of 500us. - tModeRegtPrescalerRegValue604us = 0xFFF // 4095 => fRegtimer=1.65kHz, timer period of 604us. + //tModeRegtPrescalerRegValue25us = 0x0A9 // 169 => fRegtimer=40kHz, timer period of 25μs. + //tModeRegtPrescalerRegValue38us = 0x0FF // 255 => fRegtimer=26kHz, timer period of 38μs. + //tModeRegtPrescalerRegValue500us = 0xD3E // 3390 => fRegtimer= 2kHz, timer period of 500us. + //tModeRegtPrescalerRegValue604us = 0xFFF // 4095 => fRegtimer=1.65kHz, timer period of 604us. ) const ( @@ -399,8 +399,8 @@ const ( const ( // ------------ unused commands -------------------- - regTCounterValueH = 0x2E // shows the 16-bit timer value - regTCounterValueL = 0x2F + //regTCounterValueH = 0x2E // shows the 16-bit timer value + //regTCounterValueL = 0x2F // Page 3: Test Registers // 0x30 // reserved for future use diff --git a/drivers/common/mfrc522/mfrc522_picc.go b/drivers/common/mfrc522/mfrc522_picc.go index 07800f78b..3723181dc 100644 --- a/drivers/common/mfrc522/mfrc522_picc.go +++ b/drivers/common/mfrc522/mfrc522_picc.go @@ -36,7 +36,7 @@ const ( piccCommandMFRegTRANSFER = 0xB0 // Writes the contents of the internal data register to a block. // The commands used for MIFARE Ultralight (from http://www.nxp.com/documents/dataRegsheet/MF0ICU1.pdf, Section 8.6) // The piccCommandMFRegREAD and piccCommandMFRegWRITE can also be used for MIFARE Ultralight. - piccCommandULRegWRITE = 0xA2 // Writes one 4 byte page to the PICC. + //piccCommandULRegWRITE = 0xA2 // Writes one 4 byte page to the PICC. ) const piccReadWriteAuthBlock = uint8(11) diff --git a/drivers/gpio/aip1640_driver.go b/drivers/gpio/aip1640_driver.go index c8327cfa3..32b6c54e9 100644 --- a/drivers/gpio/aip1640_driver.go +++ b/drivers/gpio/aip1640_driver.go @@ -48,15 +48,15 @@ func NewAIP1640Driver(a gobot.Connection, clockPin string, dataPin string) *AIP1 } // Start initializes the tm1638, it uses a SPI-like communication protocol -func (a *AIP1640Driver) Start() (err error) { - a.pinData.On() - a.pinClock.On() - - return +func (a *AIP1640Driver) Start() error { + if err := a.pinData.On(); err != nil { + return err + } + return a.pinClock.On() } // Halt implements the Driver interface -func (a *AIP1640Driver) Halt() (err error) { return } +func (a *AIP1640Driver) Halt() error { return nil } // Name returns the AIP1640Drivers name func (a *AIP1640Driver) Name() string { return a.name } @@ -78,18 +78,28 @@ func (a *AIP1640Driver) SetIntensity(level byte) { } // Display sends the buffer to the display (ie. turns on/off the corresponding LEDs) -func (a *AIP1640Driver) Display() { +func (a *AIP1640Driver) Display() error { for i := 0; i < 8; i++ { - a.sendData(byte(i), a.buffer[i]) + if err := a.sendData(byte(i), a.buffer[i]); err != nil { + return err + } - a.pinData.Off() - a.pinClock.Off() + if err := a.pinData.Off(); err != nil { + return err + } + if err := a.pinClock.Off(); err != nil { + return err + } time.Sleep(1 * time.Millisecond) - a.pinClock.On() - a.pinData.On() + if err := a.pinClock.On(); err != nil { + return err + } + if err := a.pinData.On(); err != nil { + return err + } } - a.sendCommand(AIP1640DispCtrl | a.intensity) + return a.sendCommand(AIP1640DispCtrl | a.intensity) } // Clear empties the buffer (turns off all the LEDs) @@ -128,33 +138,55 @@ func (a *AIP1640Driver) DrawMatrix(data [8]byte) { } // sendCommand is an auxiliary function to send commands to the AIP1640Driver module -func (a *AIP1640Driver) sendCommand(cmd byte) { - a.pinData.Off() - a.send(cmd) - a.pinData.On() +func (a *AIP1640Driver) sendCommand(cmd byte) error { + if err := a.pinData.Off(); err != nil { + return err + } + if err := a.send(cmd); err != nil { + return err + } + return a.pinData.On() } // sendData is an auxiliary function to send data to the AIP1640Driver module -func (a *AIP1640Driver) sendData(address byte, data byte) { - a.sendCommand(AIP1640DataCmd | AIP1640FixedAddr) - a.pinData.Off() - a.send(AIP1640AddrCmd | address) - a.send(data) - a.pinData.On() +func (a *AIP1640Driver) sendData(address byte, data byte) error { + if err := a.sendCommand(AIP1640DataCmd | AIP1640FixedAddr); err != nil { + return err + } + if err := a.pinData.Off(); err != nil { + return err + } + if err := a.send(AIP1640AddrCmd | address); err != nil { + return err + } + if err := a.send(data); err != nil { + return err + } + return a.pinData.On() } // send writes data on the module -func (a *AIP1640Driver) send(data byte) { +func (a *AIP1640Driver) send(data byte) error { for i := 0; i < 8; i++ { - a.pinClock.Off() + if err := a.pinClock.Off(); err != nil { + return err + } if (data & 1) > 0 { - a.pinData.On() + if err := a.pinData.On(); err != nil { + return err + } } else { - a.pinData.Off() + if err := a.pinData.Off(); err != nil { + return err + } } data >>= 1 - a.pinClock.On() + if err := a.pinClock.On(); err != nil { + return err + } } + + return nil } diff --git a/drivers/gpio/button_driver_test.go b/drivers/gpio/button_driver_test.go index e1a161b1b..aa458c88c 100644 --- a/drivers/gpio/button_driver_test.go +++ b/drivers/gpio/button_driver_test.go @@ -39,7 +39,7 @@ func TestButtonDriverStart(t *testing.T) { a := newGpioTestAdaptor() d := NewButtonDriver(a, "1") - d.Once(ButtonPush, func(data interface{}) { + _ = d.Once(ButtonPush, func(data interface{}) { gobottest.Assert(t, d.Active, true) sem <- true }) @@ -57,7 +57,7 @@ func TestButtonDriverStart(t *testing.T) { t.Errorf("Button Event \"Push\" was not published") } - d.Once(ButtonRelease, func(data interface{}) { + _ = d.Once(ButtonRelease, func(data interface{}) { gobottest.Assert(t, d.Active, false) sem <- true }) @@ -73,7 +73,7 @@ func TestButtonDriverStart(t *testing.T) { t.Errorf("Button Event \"Release\" was not published") } - d.Once(Error, func(data interface{}) { + _ = d.Once(Error, func(data interface{}) { sem <- true }) @@ -88,7 +88,7 @@ func TestButtonDriverStart(t *testing.T) { t.Errorf("Button Event \"Error\" was not published") } - d.Once(ButtonPush, func(data interface{}) { + _ = d.Once(ButtonPush, func(data interface{}) { sem <- true }) @@ -112,7 +112,7 @@ func TestButtonDriverDefaultState(t *testing.T) { d := NewButtonDriver(a, "1") d.DefaultState = 1 - d.Once(ButtonPush, func(data interface{}) { + _ = d.Once(ButtonPush, func(data interface{}) { gobottest.Assert(t, d.Active, true) sem <- true }) @@ -130,7 +130,7 @@ func TestButtonDriverDefaultState(t *testing.T) { t.Errorf("Button Event \"Push\" was not published") } - d.Once(ButtonRelease, func(data interface{}) { + _ = d.Once(ButtonRelease, func(data interface{}) { gobottest.Assert(t, d.Active, false) sem <- true }) diff --git a/drivers/gpio/buzzer_driver_test.go b/drivers/gpio/buzzer_driver_test.go index 7d1fac14d..3edb43ea5 100644 --- a/drivers/gpio/buzzer_driver_test.go +++ b/drivers/gpio/buzzer_driver_test.go @@ -38,10 +38,10 @@ func TestBuzzerDriverHalt(t *testing.T) { func TestBuzzerDriverToggle(t *testing.T) { d := initTestBuzzerDriver(newGpioTestAdaptor()) - d.Off() - d.Toggle() + _ = d.Off() + _ = d.Toggle() gobottest.Assert(t, d.State(), true) - d.Toggle() + _ = d.Toggle() gobottest.Assert(t, d.State(), false) } diff --git a/drivers/gpio/easy_driver.go b/drivers/gpio/easy_driver.go index 3196b89ef..fdde14f2a 100644 --- a/drivers/gpio/easy_driver.go +++ b/drivers/gpio/easy_driver.go @@ -5,6 +5,7 @@ import ( "strconv" "time" + "github.com/hashicorp/go-multierror" "gobot.io/x/gobot/v2" ) @@ -89,19 +90,18 @@ func (d *EasyDriver) SetName(n string) { d.name = n } func (d *EasyDriver) Connection() gobot.Connection { return d.connection.(gobot.Connection) } // Start implements the Driver interface -func (d *EasyDriver) Start() (err error) { return } +func (d *EasyDriver) Start() error { return nil } // Halt implements the Driver interface; stops running the stepper -func (d *EasyDriver) Halt() (err error) { - d.Stop() - return +func (d *EasyDriver) Halt() error { + return d.Stop() } // Move the motor given number of degrees at current speed. -func (d *EasyDriver) Move(degs int) (err error) { +func (d *EasyDriver) Move(degs int) error { if d.moving { // don't do anything if already moving - return + return nil } d.moving = true @@ -113,57 +113,65 @@ func (d *EasyDriver) Move(degs int) (err error) { break } - d.Step() + if err := d.Step(); err != nil { + return err + } } d.moving = false - return + return nil } // Step the stepper 1 step -func (d *EasyDriver) Step() (err error) { +func (d *EasyDriver) Step() error { stepsPerRev := d.GetMaxSpeed() // a valid steps occurs for a low to high transition - d.connection.DigitalWrite(d.stepPin, 0) + if err := d.connection.DigitalWrite(d.stepPin, 0); err != nil { + return err + } // 1 minute / steps per revolution / revolutions per minute // let's keep it as Microseconds so we only have to do integer math time.Sleep(time.Duration(60*1000*1000/stepsPerRev/d.rpm) * time.Microsecond) - d.connection.DigitalWrite(d.stepPin, 1) + if err := d.connection.DigitalWrite(d.stepPin, 1); err != nil { + return err + } // increment or decrement the number of steps by 1 d.stepNum += int(d.dir) - return + return nil } // Run the stepper continuously -func (d *EasyDriver) Run() (err error) { +func (d *EasyDriver) Run() error { if d.moving { // don't do anything if already moving - return + return nil } d.moving = true go func() { for d.moving { - d.Step() + if err := d.Step(); err != nil { + panic(err) + } } }() - return + return nil } // Stop running the stepper -func (d *EasyDriver) Stop() (err error) { +func (d *EasyDriver) Stop() error { d.moving = false - return + return nil } // SetDirection sets the direction to be moving. Valid directions are "cw" or "ccw" -func (d *EasyDriver) SetDirection(dir string) (err error) { +func (d *EasyDriver) SetDirection(dir string) error { // can't change direct if dirPin isn't set if d.dirPin == "" { return errors.New("dirPin is not set") @@ -171,17 +179,18 @@ func (d *EasyDriver) SetDirection(dir string) (err error) { if dir == "ccw" { d.dir = -1 - d.connection.DigitalWrite(d.dirPin, 1) // high is ccw - } else { // default to cw, even if user specified wrong value - d.dir = 1 - d.connection.DigitalWrite(d.dirPin, 0) // low is cw + // high is ccw + return d.connection.DigitalWrite(d.dirPin, 1) } - return + // default to cw, even if user specified wrong value + d.dir = 1 + // low is cw + return d.connection.DigitalWrite(d.dirPin, 0) } // SetSpeed sets the speed of the motor in RPMs. 1 is the lowest and GetMaxSpeed is the highest -func (d *EasyDriver) SetSpeed(rpm uint) (err error) { +func (d *EasyDriver) SetSpeed(rpm uint) error { if rpm < 1 { d.rpm = 1 } else if rpm > d.GetMaxSpeed() { @@ -190,7 +199,7 @@ func (d *EasyDriver) SetSpeed(rpm uint) (err error) { d.rpm = rpm } - return + return nil } // GetMaxSpeed returns the max speed of the stepper @@ -209,32 +218,39 @@ func (d *EasyDriver) IsMoving() bool { } // Enable enables all motor output -func (d *EasyDriver) Enable() (err error) { +func (d *EasyDriver) Enable() error { // can't enable if enPin isn't set. This is fine normally since it will be enabled by default if d.enPin == "" { return errors.New("enPin is not set. Board is enabled by default") } - d.enabled = true - d.connection.DigitalWrite(d.enPin, 0) // enPin is active low + // enPin is active low + if err := d.connection.DigitalWrite(d.enPin, 0); err != nil { + return err + } - return + d.enabled = true + return nil } // Disable disables all motor output -func (d *EasyDriver) Disable() (err error) { +func (d *EasyDriver) Disable() error { // can't disable if enPin isn't set if d.enPin == "" { return errors.New("enPin is not set") } - // let's stop the motor first - d.Stop() + // let's stop the motor first, but do not return on error + err := d.Stop() - d.enabled = false - d.connection.DigitalWrite(d.enPin, 1) // enPin is active low + // enPin is active low + if e := d.connection.DigitalWrite(d.enPin, 1); e != nil { + err = multierror.Append(err, e) + } else { + d.enabled = false + } - return + return err } // IsEnabled returns a bool stating whether motor is enabled @@ -243,36 +259,44 @@ func (d *EasyDriver) IsEnabled() bool { } // Sleep puts the driver to sleep and disables all motor output. Low power mode. -func (d *EasyDriver) Sleep() (err error) { +func (d *EasyDriver) Sleep() error { // can't sleep if sleepPin isn't set if d.sleepPin == "" { return errors.New("sleepPin is not set") } // let's stop the motor first - d.Stop() + err := d.Stop() - d.sleeping = true - d.connection.DigitalWrite(d.sleepPin, 0) // sleepPin is active low + // sleepPin is active low + if e := d.connection.DigitalWrite(d.sleepPin, 0); e != nil { + err = multierror.Append(err, e) + } else { + d.sleeping = true + } - return + return err } // Wake wakes up the driver -func (d *EasyDriver) Wake() (err error) { +func (d *EasyDriver) Wake() error { // can't wake if sleepPin isn't set if d.sleepPin == "" { return errors.New("sleepPin is not set") } + // sleepPin is active low + if err := d.connection.DigitalWrite(d.sleepPin, 1); err != nil { + return err + } + d.sleeping = false - d.connection.DigitalWrite(d.sleepPin, 1) // sleepPin is active low // we need to wait 1ms after sleeping before doing a step to charge the step pump (according to data sheet) // this will ensure that happens time.Sleep(1 * time.Millisecond) - return + return nil } // IsSleeping returns a bool stating whether motor is enabled diff --git a/drivers/gpio/easy_driver_test.go b/drivers/gpio/easy_driver_test.go index c873009e9..baaf69170 100644 --- a/drivers/gpio/easy_driver_test.go +++ b/drivers/gpio/easy_driver_test.go @@ -38,21 +38,21 @@ func TestEasyDriverSetName(t *testing.T) { func TestEasyDriverStart(t *testing.T) { d := initEasyDriver() - d.Start() + _ = d.Start() // noop - no error occurred } func TestEasyDriverHalt(t *testing.T) { d := initEasyDriver() - d.Run() + _ = d.Run() gobottest.Assert(t, d.IsMoving(), true) - d.Halt() + _ = d.Halt() gobottest.Assert(t, d.IsMoving(), false) } func TestEasyDriverMove(t *testing.T) { d := initEasyDriver() - d.Move(2) + _ = d.Move(2) time.Sleep(2 * time.Millisecond) gobottest.Assert(t, d.GetCurrentStep(), 4) gobottest.Assert(t, d.IsMoving(), false) @@ -60,41 +60,41 @@ func TestEasyDriverMove(t *testing.T) { func TestEasyDriverRun(t *testing.T) { d := initEasyDriver() - d.Run() + _ = d.Run() gobottest.Assert(t, d.IsMoving(), true) - d.Run() + _ = d.Run() gobottest.Assert(t, d.IsMoving(), true) } func TestEasyDriverStop(t *testing.T) { d := initEasyDriver() - d.Run() + _ = d.Run() gobottest.Assert(t, d.IsMoving(), true) - d.Stop() + _ = d.Stop() gobottest.Assert(t, d.IsMoving(), false) } func TestEasyDriverStep(t *testing.T) { d := initEasyDriver() - d.Step() + _ = d.Step() gobottest.Assert(t, d.GetCurrentStep(), 1) - d.Step() - d.Step() - d.Step() + _ = d.Step() + _ = d.Step() + _ = d.Step() gobottest.Assert(t, d.GetCurrentStep(), 4) - d.SetDirection("ccw") - d.Step() + _ = d.SetDirection("ccw") + _ = d.Step() gobottest.Assert(t, d.GetCurrentStep(), 3) } func TestEasyDriverSetDirection(t *testing.T) { d := initEasyDriver() gobottest.Assert(t, d.dir, int8(1)) - d.SetDirection("cw") + _ = d.SetDirection("cw") gobottest.Assert(t, d.dir, int8(1)) - d.SetDirection("ccw") + _ = d.SetDirection("ccw") gobottest.Assert(t, d.dir, int8(-1)) - d.SetDirection("nothing") + _ = d.SetDirection("nothing") gobottest.Assert(t, d.dir, int8(1)) } @@ -108,11 +108,11 @@ func TestEasyDriverSetDirectionNoPin(t *testing.T) { func TestEasyDriverSetSpeed(t *testing.T) { d := initEasyDriver() gobottest.Assert(t, d.rpm, uint(stepsPerRev/4)) // default speed of 720/4 - d.SetSpeed(0) + _ = d.SetSpeed(0) gobottest.Assert(t, d.rpm, uint(1)) - d.SetSpeed(200) + _ = d.SetSpeed(200) gobottest.Assert(t, d.rpm, uint(200)) - d.SetSpeed(1000) + _ = d.SetSpeed(1000) gobottest.Assert(t, d.rpm, uint(stepsPerRev)) } @@ -124,13 +124,13 @@ func TestEasyDriverGetMaxSpeed(t *testing.T) { func TestEasyDriverSleep(t *testing.T) { // let's test basic functionality d := initEasyDriver() - d.Sleep() + _ = d.Sleep() gobottest.Assert(t, d.IsSleeping(), true) // let's make sure it stops first d = initEasyDriver() - d.Run() - d.Sleep() + _ = d.Run() + _ = d.Sleep() gobottest.Assert(t, d.IsSleeping(), true) gobottest.Assert(t, d.IsMoving(), false) } @@ -147,18 +147,18 @@ func TestEasyDriverSleepNoPin(t *testing.T) { func TestEasyDriverWake(t *testing.T) { // let's test basic functionality d := initEasyDriver() - d.Sleep() + _ = d.Sleep() gobottest.Assert(t, d.IsSleeping(), true) - d.Wake() + _ = d.Wake() gobottest.Assert(t, d.IsSleeping(), false) } func TestEasyDriverEnable(t *testing.T) { // let's test basic functionality d := initEasyDriver() - d.Disable() + _ = d.Disable() gobottest.Assert(t, d.IsEnabled(), false) - d.Enable() + _ = d.Enable() gobottest.Assert(t, d.IsEnabled(), true) } @@ -174,13 +174,13 @@ func TestEasyDriverEnableNoPin(t *testing.T) { func TestEasyDriverDisable(t *testing.T) { // let's test basic functionality d := initEasyDriver() - d.Disable() + _ = d.Disable() gobottest.Assert(t, d.IsEnabled(), false) // let's make sure it stops first d = initEasyDriver() - d.Run() - d.Disable() + _ = d.Run() + _ = d.Disable() gobottest.Assert(t, d.IsEnabled(), false) gobottest.Assert(t, d.IsMoving(), false) } diff --git a/drivers/gpio/grove_drivers_test.go b/drivers/gpio/grove_drivers_test.go index 3dd3e97b4..35f3ac840 100644 --- a/drivers/gpio/grove_drivers_test.go +++ b/drivers/gpio/grove_drivers_test.go @@ -59,10 +59,10 @@ func TestDigitalDriverHalt(t *testing.T) { } // Start the driver and allow for multiple digital reads - driver.Start() + _ = driver.Start() time.Sleep(20 * time.Millisecond) - driver.Halt() + _ = driver.Halt() lastCallCount := atomic.LoadInt32(&callCount) // If driver was not halted, digital reads would still continue time.Sleep(20 * time.Millisecond) @@ -94,7 +94,7 @@ func TestDriverPublishesError(t *testing.T) { gobottest.Assert(t, driver.Start(), nil) // expect error - driver.Once(driver.Event(Error), func(data interface{}) { + _ = driver.Once(driver.Event(Error), func(data interface{}) { gobottest.Assert(t, data.(error).Error(), "read error") close(sem) }) @@ -106,7 +106,7 @@ func TestDriverPublishesError(t *testing.T) { } // Cleanup - driver.Halt() + _ = driver.Halt() } } diff --git a/drivers/gpio/hd44780_driver_test.go b/drivers/gpio/hd44780_driver_test.go index d13d33a85..5a4ccadb7 100644 --- a/drivers/gpio/hd44780_driver_test.go +++ b/drivers/gpio/hd44780_driver_test.go @@ -12,9 +12,12 @@ import ( var _ gobot.Driver = (*HD44780Driver)(nil) // --------- HELPERS -func initTestHD44780Driver() (driver *HD44780Driver) { - driver, _ = initTestHD44780Driver4BitModeWithStubbedAdaptor() - return +func initTestHD44780Driver() *HD44780Driver { + d, _ := initTestHD44780Driver4BitModeWithStubbedAdaptor() + if err := d.Start(); err != nil { + panic(err) + } + return d } func initTestHD44780Driver4BitModeWithStubbedAdaptor() (*HD44780Driver, *gpioTestAdaptor) { @@ -47,7 +50,8 @@ func initTestHD44780Driver8BitModeWithStubbedAdaptor() (*HD44780Driver, *gpioTes // --------- TESTS func TestHD44780Driver(t *testing.T) { - var a interface{} = initTestHD44780Driver() + d, _ := initTestHD44780Driver4BitModeWithStubbedAdaptor() + var a interface{} = d _, ok := a.(*HD44780Driver) if !ok { t.Errorf("NewHD44780Driver() should have returned a *HD44780Driver") @@ -56,23 +60,22 @@ func TestHD44780Driver(t *testing.T) { func TestHD44780DriverHalt(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.Halt(), nil) } func TestHD44780DriverDefaultName(t *testing.T) { - d := initTestHD44780Driver() + d, _ := initTestHD44780Driver4BitModeWithStubbedAdaptor() gobottest.Assert(t, strings.HasPrefix(d.Name(), "HD44780Driver"), true) } func TestHD44780DriverSetName(t *testing.T) { - d := initTestHD44780Driver() + d, _ := initTestHD44780Driver4BitModeWithStubbedAdaptor() d.SetName("my driver") gobottest.Assert(t, d.Name(), "my driver") } func TestHD44780DriverStart(t *testing.T) { - d := initTestHD44780Driver() + d, _ := initTestHD44780Driver4BitModeWithStubbedAdaptor() gobottest.Assert(t, d.Start(), nil) } @@ -109,11 +112,11 @@ func TestHD44780DriverWrite(t *testing.T) { var d *HD44780Driver d, _ = initTestHD44780Driver4BitModeWithStubbedAdaptor() - d.Start() + _ = d.Start() gobottest.Assert(t, d.Write("hello gobot"), nil) d, _ = initTestHD44780Driver8BitModeWithStubbedAdaptor() - d.Start() + _ = d.Start() gobottest.Assert(t, d.Write("hello gobot"), nil) } @@ -125,38 +128,34 @@ func TestHD44780DriverWriteError(t *testing.T) { a.testAdaptorDigitalWrite = func(string, byte) (err error) { return errors.New("write error") } - d.Start() + _ = d.Start() gobottest.Assert(t, d.Write("hello gobot"), errors.New("write error")) d, a = initTestHD44780Driver8BitModeWithStubbedAdaptor() a.testAdaptorDigitalWrite = func(string, byte) (err error) { return errors.New("write error") } - d.Start() + _ = d.Start() gobottest.Assert(t, d.Write("hello gobot"), errors.New("write error")) } func TestHD44780DriverClear(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.Clear(), nil) } func TestHD44780DriverHome(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.Home(), nil) } func TestHD44780DriverSetCursor(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.SetCursor(0, 3), nil) } func TestHD44780DriverSetCursorInvalid(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.SetCursor(-1, 3), errors.New("Invalid position value (-1, 3), range (1, 15)")) gobottest.Assert(t, d.SetCursor(2, 3), errors.New("Invalid position value (2, 3), range (1, 15)")) gobottest.Assert(t, d.SetCursor(0, -1), errors.New("Invalid position value (0, -1), range (1, 15)")) @@ -165,86 +164,72 @@ func TestHD44780DriverSetCursorInvalid(t *testing.T) { func TestHD44780DriverDisplayOn(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.Display(true), nil) } func TestHD44780DriverDisplayOff(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.Display(false), nil) } func TestHD44780DriverCursorOn(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.Cursor(true), nil) } func TestHD44780DriverCursorOff(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.Cursor(false), nil) } func TestHD44780DriverBlinkOn(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.Blink(true), nil) } func TestHD44780DriverBlinkOff(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.Blink(false), nil) } func TestHD44780DriverScrollLeft(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.ScrollLeft(), nil) } func TestHD44780DriverScrollRight(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.ScrollRight(), nil) } func TestHD44780DriverLeftToRight(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.LeftToRight(), nil) } func TestHD44780DriverRightToLeft(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.RightToLeft(), nil) } func TestHD44780DriverSendCommand(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.SendCommand(0x33), nil) } func TestHD44780DriverWriteChar(t *testing.T) { d := initTestHD44780Driver() - d.Start() gobottest.Assert(t, d.WriteChar(0x41), nil) } func TestHD44780DriverCreateChar(t *testing.T) { d := initTestHD44780Driver() - d.Start() charMap := [8]byte{1, 2, 3, 4, 5, 6, 7, 8} gobottest.Assert(t, d.CreateChar(0, charMap), nil) } func TestHD44780DriverCreateCharError(t *testing.T) { d := initTestHD44780Driver() - d.Start() charMap := [8]byte{1, 2, 3, 4, 5, 6, 7, 8} gobottest.Assert(t, d.CreateChar(8, charMap), errors.New("can't set a custom character at a position greater than 7")) } diff --git a/drivers/gpio/helpers_test.go b/drivers/gpio/helpers_test.go index fe3849c09..959ba7c65 100644 --- a/drivers/gpio/helpers_test.go +++ b/drivers/gpio/helpers_test.go @@ -9,12 +9,6 @@ func (t *gpioTestBareAdaptor) Finalize() (err error) { return } func (t *gpioTestBareAdaptor) Name() string { return "" } func (t *gpioTestBareAdaptor) SetName(n string) {} -type gpioTestDigitalWriter struct { - gpioTestBareAdaptor -} - -func (t *gpioTestDigitalWriter) DigitalWrite(string, byte) (err error) { return } - type gpioTestAdaptor struct { name string port string diff --git a/drivers/gpio/led_driver_test.go b/drivers/gpio/led_driver_test.go index b7a3b3cbc..cd6fc57f0 100644 --- a/drivers/gpio/led_driver_test.go +++ b/drivers/gpio/led_driver_test.go @@ -63,10 +63,10 @@ func TestLedDriverHalt(t *testing.T) { func TestLedDriverToggle(t *testing.T) { d := initTestLedDriver() - d.Off() - d.Toggle() + _ = d.Off() + _ = d.Toggle() gobottest.Assert(t, d.State(), true) - d.Toggle() + _ = d.Toggle() gobottest.Assert(t, d.State(), false) } diff --git a/drivers/gpio/makey_button_driver_test.go b/drivers/gpio/makey_button_driver_test.go index cf5857fe5..0fb54c144 100644 --- a/drivers/gpio/makey_button_driver_test.go +++ b/drivers/gpio/makey_button_driver_test.go @@ -49,7 +49,7 @@ func TestMakeyButtonDriverStart(t *testing.T) { gobottest.Assert(t, d.Start(), nil) - d.Once(ButtonPush, func(data interface{}) { + _ = d.Once(ButtonPush, func(data interface{}) { gobottest.Assert(t, d.Active, true) sem <- true }) @@ -65,7 +65,7 @@ func TestMakeyButtonDriverStart(t *testing.T) { t.Errorf("MakeyButton Event \"Push\" was not published") } - d.Once(ButtonRelease, func(data interface{}) { + _ = d.Once(ButtonRelease, func(data interface{}) { gobottest.Assert(t, d.Active, false) sem <- true }) @@ -81,7 +81,7 @@ func TestMakeyButtonDriverStart(t *testing.T) { t.Errorf("MakeyButton Event \"Release\" was not published") } - d.Once(Error, func(data interface{}) { + _ = d.Once(Error, func(data interface{}) { gobottest.Assert(t, data.(error).Error(), "digital read error") sem <- true }) @@ -98,7 +98,7 @@ func TestMakeyButtonDriverStart(t *testing.T) { } // send a halt message - d.Once(ButtonRelease, func(data interface{}) { + _ = d.Once(ButtonRelease, func(data interface{}) { sem <- true }) diff --git a/drivers/gpio/max7219_driver.go b/drivers/gpio/max7219_driver.go index 9693ec304..216d7e26d 100644 --- a/drivers/gpio/max7219_driver.go +++ b/drivers/gpio/max7219_driver.go @@ -1,6 +1,7 @@ package gpio import ( + "github.com/hashicorp/go-multierror" "gobot.io/x/gobot/v2" ) @@ -53,23 +54,37 @@ func NewMAX7219Driver(a gobot.Connection, clockPin string, dataPin string, csPin } // Start initializes the max7219, it uses a SPI-like communication protocol -func (a *MAX7219Driver) Start() (err error) { - a.pinData.On() - a.pinClock.On() - a.pinCS.On() - - a.All(MAX7219ScanLimit, 0x07) - a.All(MAX7219DecodeMode, 0x00) - a.All(MAX7219Shutdown, 0x01) - a.All(MAX7219DisplayTest, 0x00) - a.ClearAll() - a.All(MAX7219Intensity, 0x0f) - - return +func (a *MAX7219Driver) Start() error { + if err := a.pinData.On(); err != nil { + return err + } + if err := a.pinClock.On(); err != nil { + return err + } + if err := a.pinCS.On(); err != nil { + return err + } + + if err := a.All(MAX7219ScanLimit, 0x07); err != nil { + return err + } + if err := a.All(MAX7219DecodeMode, 0x00); err != nil { + return err + } + if err := a.All(MAX7219Shutdown, 0x01); err != nil { + return err + } + if err := a.All(MAX7219DisplayTest, 0x00); err != nil { + return err + } + if err := a.ClearAll(); err != nil { + return err + } + return a.All(MAX7219Intensity, 0x0f) } // Halt implements the Driver interface -func (a *MAX7219Driver) Halt() (err error) { return } +func (a *MAX7219Driver) Halt() error { return nil } // Name returns the MAX7219Drivers name func (a *MAX7219Driver) Name() string { return a.name } @@ -83,74 +98,102 @@ func (a *MAX7219Driver) Connection() gobot.Connection { } // SetIntensity changes the intensity (from 1 to 7) of the display -func (a *MAX7219Driver) SetIntensity(level byte) { +func (a *MAX7219Driver) SetIntensity(level byte) error { if level > 15 { level = 15 } - a.All(MAX7219Intensity, level) + return a.All(MAX7219Intensity, level) } // ClearAll turns off all LEDs of all modules -func (a *MAX7219Driver) ClearAll() { +func (a *MAX7219Driver) ClearAll() error { + var err error for i := 1; i <= 8; i++ { - a.All(byte(i), 0) + if e := a.All(byte(i), 0); e != nil { + err = multierror.Append(err, e) + } } + + return err } // ClearOne turns off all LEDs of the given module -func (a *MAX7219Driver) ClearOne(which uint) { +func (a *MAX7219Driver) ClearOne(which uint) error { + var err error for i := 1; i <= 8; i++ { - a.One(which, byte(i), 0) + if e := a.One(which, byte(i), 0); e != nil { + err = multierror.Append(err, e) + } } -} -// sendData is an auxiliary function to send data to the MAX7219Driver module -func (a *MAX7219Driver) sendData(address byte, data byte) { - a.pinCS.Off() - a.send(address) - a.send(data) - a.pinCS.On() + return err } // send writes data on the module -func (a *MAX7219Driver) send(data byte) { +func (a *MAX7219Driver) send(data byte) error { var i byte for i = 8; i > 0; i-- { mask := byte(0x01 << (i - 1)) - a.pinClock.Off() + if err := a.pinClock.Off(); err != nil { + return err + } if data&mask > 0 { - a.pinData.On() + if err := a.pinData.On(); err != nil { + return err + } } else { - a.pinData.Off() + if err := a.pinData.Off(); err != nil { + return err + } + } + if err := a.pinClock.On(); err != nil { + return err } - a.pinClock.On() } + + return nil } // All sends the same data to all the modules -func (a *MAX7219Driver) All(address byte, data byte) { - a.pinCS.Off() +func (a *MAX7219Driver) All(address byte, data byte) error { + if err := a.pinCS.Off(); err != nil { + return err + } var c uint for c = 0; c < a.count; c++ { - a.send(address) - a.send(data) + if err := a.send(address); err != nil { + return err + } + if err := a.send(data); err != nil { + return err + } } - a.pinCS.On() + return a.pinCS.On() } // One sends data to a specific module -func (a *MAX7219Driver) One(which uint, address byte, data byte) { - a.pinCS.Off() +func (a *MAX7219Driver) One(which uint, address byte, data byte) error { + if err := a.pinCS.Off(); err != nil { + return err + } var c uint for c = 0; c < a.count; c++ { if c == which { - a.send(address) - a.send(data) + if err := a.send(address); err != nil { + return err + } + if err := a.send(data); err != nil { + return err + } } else { - a.send(0) - a.send(0) + if err := a.send(0); err != nil { + return err + } + if err := a.send(0); err != nil { + return err + } } } - a.pinCS.On() + return a.pinCS.On() } diff --git a/drivers/gpio/motor_driver_test.go b/drivers/gpio/motor_driver_test.go index e1107d6fe..aa382fec3 100644 --- a/drivers/gpio/motor_driver_test.go +++ b/drivers/gpio/motor_driver_test.go @@ -41,76 +41,76 @@ func TestMotorDriverIsOn(t *testing.T) { func TestMotorDriverIsOff(t *testing.T) { d := initTestMotorDriver() - d.Off() + _ = d.Off() gobottest.Assert(t, d.IsOff(), true) } func TestMotorDriverOn(t *testing.T) { d := initTestMotorDriver() d.CurrentMode = "digital" - d.On() + _ = d.On() gobottest.Assert(t, d.CurrentState, uint8(1)) d.CurrentMode = "analog" d.CurrentSpeed = 0 - d.On() + _ = d.On() gobottest.Assert(t, d.CurrentSpeed, uint8(255)) } func TestMotorDriverOff(t *testing.T) { d := initTestMotorDriver() d.CurrentMode = "digital" - d.Off() + _ = d.Off() gobottest.Assert(t, d.CurrentState, uint8(0)) d.CurrentMode = "analog" d.CurrentSpeed = 100 - d.Off() + _ = d.Off() gobottest.Assert(t, d.CurrentSpeed, uint8(0)) } func TestMotorDriverToggle(t *testing.T) { d := initTestMotorDriver() - d.Off() - d.Toggle() + _ = d.Off() + _ = d.Toggle() gobottest.Assert(t, d.IsOn(), true) - d.Toggle() + _ = d.Toggle() gobottest.Assert(t, d.IsOn(), false) } func TestMotorDriverMin(t *testing.T) { d := initTestMotorDriver() - d.Min() + _ = d.Min() } func TestMotorDriverMax(t *testing.T) { d := initTestMotorDriver() - d.Max() + _ = d.Max() } func TestMotorDriverSpeed(t *testing.T) { d := initTestMotorDriver() - d.Speed(100) + _ = d.Speed(100) } func TestMotorDriverForward(t *testing.T) { d := initTestMotorDriver() - d.Forward(100) + _ = d.Forward(100) gobottest.Assert(t, d.CurrentSpeed, uint8(100)) gobottest.Assert(t, d.CurrentDirection, "forward") } func TestMotorDriverBackward(t *testing.T) { d := initTestMotorDriver() - d.Backward(100) + _ = d.Backward(100) gobottest.Assert(t, d.CurrentSpeed, uint8(100)) gobottest.Assert(t, d.CurrentDirection, "backward") } func TestMotorDriverDirection(t *testing.T) { d := initTestMotorDriver() - d.Direction("none") + _ = d.Direction("none") d.DirectionPin = "2" - d.Direction("forward") - d.Direction("backward") + _ = d.Direction("forward") + _ = d.Direction("backward") } func TestMotorDriverDigital(t *testing.T) { @@ -120,9 +120,9 @@ func TestMotorDriverDigital(t *testing.T) { d.ForwardPin = "2" d.BackwardPin = "3" - d.On() + _ = d.On() gobottest.Assert(t, d.CurrentState, uint8(1)) - d.Off() + _ = d.Off() gobottest.Assert(t, d.CurrentState, uint8(0)) } diff --git a/drivers/gpio/pir_motion_driver_test.go b/drivers/gpio/pir_motion_driver_test.go index 7d73c5753..6cfc755b1 100644 --- a/drivers/gpio/pir_motion_driver_test.go +++ b/drivers/gpio/pir_motion_driver_test.go @@ -41,7 +41,7 @@ func TestPIRMotionDriverStart(t *testing.T) { gobottest.Assert(t, d.Start(), nil) - d.Once(MotionDetected, func(data interface{}) { + _ = d.Once(MotionDetected, func(data interface{}) { gobottest.Assert(t, d.Active, true) sem <- true }) @@ -57,7 +57,7 @@ func TestPIRMotionDriverStart(t *testing.T) { t.Errorf("PIRMotionDriver Event \"MotionDetected\" was not published") } - d.Once(MotionStopped, func(data interface{}) { + _ = d.Once(MotionStopped, func(data interface{}) { gobottest.Assert(t, d.Active, false) sem <- true }) @@ -73,7 +73,7 @@ func TestPIRMotionDriverStart(t *testing.T) { t.Errorf("PIRMotionDriver Event \"MotionStopped\" was not published") } - d.Once(Error, func(data interface{}) { + _ = d.Once(Error, func(data interface{}) { sem <- true }) diff --git a/drivers/gpio/relay_driver_test.go b/drivers/gpio/relay_driver_test.go index bb3475864..12160357a 100644 --- a/drivers/gpio/relay_driver_test.go +++ b/drivers/gpio/relay_driver_test.go @@ -54,13 +54,13 @@ func TestRelayDriverToggle(t *testing.T) { return nil }) - d.Off() + _ = d.Off() gobottest.Assert(t, d.State(), false) gobottest.Assert(t, lastVal, byte(0)) - d.Toggle() + _ = d.Toggle() gobottest.Assert(t, d.State(), true) gobottest.Assert(t, lastVal, byte(1)) - d.Toggle() + _ = d.Toggle() gobottest.Assert(t, d.State(), false) gobottest.Assert(t, lastVal, byte(0)) } @@ -74,13 +74,13 @@ func TestRelayDriverToggleInverted(t *testing.T) { }) d.Inverted = true - d.Off() + _ = d.Off() gobottest.Assert(t, d.State(), false) gobottest.Assert(t, lastVal, byte(1)) - d.Toggle() + _ = d.Toggle() gobottest.Assert(t, d.State(), true) gobottest.Assert(t, lastVal, byte(0)) - d.Toggle() + _ = d.Toggle() gobottest.Assert(t, d.State(), false) gobottest.Assert(t, lastVal, byte(1)) } diff --git a/drivers/gpio/rgb_led_driver_test.go b/drivers/gpio/rgb_led_driver_test.go index b4fa5e820..2e9ffc9ca 100644 --- a/drivers/gpio/rgb_led_driver_test.go +++ b/drivers/gpio/rgb_led_driver_test.go @@ -66,10 +66,10 @@ func TestRgbLedDriverHalt(t *testing.T) { func TestRgbLedDriverToggle(t *testing.T) { d := initTestRgbLedDriver() - d.Off() - d.Toggle() + _ = d.Off() + _ = d.Toggle() gobottest.Assert(t, d.State(), true) - d.Toggle() + _ = d.Toggle() gobottest.Assert(t, d.State(), false) } diff --git a/drivers/gpio/servo_driver_test.go b/drivers/gpio/servo_driver_test.go index e58c4d461..d34094d4b 100644 --- a/drivers/gpio/servo_driver_test.go +++ b/drivers/gpio/servo_driver_test.go @@ -53,7 +53,7 @@ func TestServoDriverHalt(t *testing.T) { func TestServoDriverMove(t *testing.T) { d := initTestServoDriver() - d.Move(100) + _ = d.Move(100) gobottest.Assert(t, d.CurrentAngle, uint8(100)) err := d.Move(200) gobottest.Assert(t, err, ErrServoOutOfRange) @@ -61,19 +61,19 @@ func TestServoDriverMove(t *testing.T) { func TestServoDriverMin(t *testing.T) { d := initTestServoDriver() - d.Min() + _ = d.Min() gobottest.Assert(t, d.CurrentAngle, uint8(0)) } func TestServoDriverMax(t *testing.T) { d := initTestServoDriver() - d.Max() + _ = d.Max() gobottest.Assert(t, d.CurrentAngle, uint8(180)) } func TestServoDriverCenter(t *testing.T) { d := initTestServoDriver() - d.Center() + _ = d.Center() gobottest.Assert(t, d.CurrentAngle, uint8(90)) } diff --git a/drivers/gpio/stepper_driver.go b/drivers/gpio/stepper_driver.go index 427644a03..25a3d2c20 100644 --- a/drivers/gpio/stepper_driver.go +++ b/drivers/gpio/stepper_driver.go @@ -106,13 +106,15 @@ func (s *StepperDriver) SetName(n string) { s.name = n } func (s *StepperDriver) Connection() gobot.Connection { return s.connection.(gobot.Connection) } // Start implements the Driver interface and keeps running the stepper till halt is called -func (s *StepperDriver) Start() (err error) { return } +func (s *StepperDriver) Start() error { return nil } // Run continuously runs the stepper -func (s *StepperDriver) Run() (err error) { +func (s *StepperDriver) Run() error { //halt if already moving if s.moving { - s.Halt() + if err := s.Halt(); err != nil { + return err + } } s.mutex.Lock() @@ -126,16 +128,18 @@ func (s *StepperDriver) Run() (err error) { if !s.moving { break } - s.step() + if err := s.step(); err != nil { + panic(err) + } time.Sleep(delay) } }() - return + return nil } // Halt implements the Driver interface and halts the motion of the Stepper -func (s *StepperDriver) Halt() (err error) { +func (s *StepperDriver) Halt() error { s.mutex.Lock() s.moving = false s.mutex.Unlock() @@ -193,7 +197,9 @@ func (s *StepperDriver) Move(stepsToMove int) error { if s.moving { //stop previous motion - s.Halt() + if err := s.Halt(); err != nil { + return err + } } s.mutex.Lock() diff --git a/drivers/gpio/stepper_driver_test.go b/drivers/gpio/stepper_driver_test.go index 56aefeb98..d41449c30 100644 --- a/drivers/gpio/stepper_driver_test.go +++ b/drivers/gpio/stepper_driver_test.go @@ -19,15 +19,15 @@ func initStepperMotorDriver() *StepperDriver { func TestStepperDriverRun(t *testing.T) { d := initStepperMotorDriver() - d.Run() + _ = d.Run() gobottest.Assert(t, d.IsMoving(), true) } func TestStepperDriverHalt(t *testing.T) { d := initStepperMotorDriver() - d.Run() + _ = d.Run() time.Sleep(200 * time.Millisecond) - d.Halt() + _ = d.Halt() gobottest.Assert(t, d.IsMoving(), false) } @@ -46,7 +46,7 @@ func TestStepperDriverSetName(t *testing.T) { func TestStepperDriverSetDirection(t *testing.T) { dir := "backward" d := initStepperMotorDriver() - d.SetDirection(dir) + _ = d.SetDirection(dir) gobottest.Assert(t, d.direction, dir) } @@ -63,25 +63,25 @@ func TestStepperDriverInvalidDirection(t *testing.T) { func TestStepperDriverMoveForward(t *testing.T) { d := initStepperMotorDriver() - d.Move(1) + _ = d.Move(1) gobottest.Assert(t, d.GetCurrentStep(), 1) - d.Move(10) + _ = d.Move(10) gobottest.Assert(t, d.GetCurrentStep(), 11) } func TestStepperDriverMoveBackward(t *testing.T) { d := initStepperMotorDriver() - d.Move(-1) + _ = d.Move(-1) gobottest.Assert(t, d.GetCurrentStep(), stepsInRev-1) - d.Move(-10) + _ = d.Move(-10) gobottest.Assert(t, d.GetCurrentStep(), stepsInRev-11) } func TestStepperDriverMoveFullRotation(t *testing.T) { d := initStepperMotorDriver() - d.Move(stepsInRev) + _ = d.Move(stepsInRev) gobottest.Assert(t, d.GetCurrentStep(), 0) } @@ -89,7 +89,7 @@ func TestStepperDriverMotorSetSpeedMoreThanMax(t *testing.T) { d := initStepperMotorDriver() m := d.GetMaxSpeed() - d.SetSpeed(m + 1) + _ = d.SetSpeed(m + 1) gobottest.Assert(t, m, d.speed) } @@ -97,9 +97,9 @@ func TestStepperDriverMotorSetSpeedLessOrEqualMax(t *testing.T) { d := initStepperMotorDriver() m := d.GetMaxSpeed() - d.SetSpeed(m - 1) + _ = d.SetSpeed(m - 1) gobottest.Assert(t, m-1, d.speed) - d.SetSpeed(m) + _ = d.SetSpeed(m) gobottest.Assert(t, m, d.speed) } diff --git a/drivers/gpio/tm1638_driver.go b/drivers/gpio/tm1638_driver.go index 5c34593d3..4b23bb360 100644 --- a/drivers/gpio/tm1638_driver.go +++ b/drivers/gpio/tm1638_driver.go @@ -61,26 +61,38 @@ func NewTM1638Driver(a gobot.Connection, clockPin string, dataPin string, strobe } // Start initializes the tm1638, it uses a SPI-like communication protocol -func (t *TM1638Driver) Start() (err error) { +func (t *TM1638Driver) Start() error { - t.pinStrobe.On() - t.pinClock.On() + if err := t.pinStrobe.On(); err != nil { + return err + } + if err := t.pinClock.On(); err != nil { + return err + } - t.sendCommand(TM1638DataCmd) - t.sendCommand(TM1638DispCtrl | 8 | 7) + if err := t.sendCommand(TM1638DataCmd); err != nil { + return err + } + if err := t.sendCommand(TM1638DispCtrl | 8 | 7); err != nil { + return err + } - t.pinStrobe.Off() - t.send(TM1638AddrCmd) + if err := t.pinStrobe.Off(); err != nil { + return err + } + if err := t.send(TM1638AddrCmd); err != nil { + return err + } for i := 0; i < 16; i++ { - t.send(TM1638WriteDisp) + if err := t.send(TM1638WriteDisp); err != nil { + return err + } } - t.pinStrobe.On() - - return + return t.pinStrobe.On() } // Halt implements the Driver interface -func (t *TM1638Driver) Halt() (err error) { return } +func (t *TM1638Driver) Halt() error { return nil } // Name returns the TM1638Drivers name func (t *TM1638Driver) Name() string { return t.name } @@ -94,75 +106,104 @@ func (t *TM1638Driver) Connection() gobot.Connection { } // sendCommand is an auxiliary function to send commands to the TM1638 module -func (t *TM1638Driver) sendCommand(cmd byte) { - t.pinStrobe.Off() - t.send(cmd) - t.pinStrobe.On() +func (t *TM1638Driver) sendCommand(cmd byte) error { + if err := t.pinStrobe.Off(); err != nil { + return err + } + if err := t.send(cmd); err != nil { + return err + } + return t.pinStrobe.On() } // send writes data on the module -func (t *TM1638Driver) send(data byte) { +func (t *TM1638Driver) send(data byte) error { for i := 0; i < 8; i++ { - t.pinClock.Off() + if err := t.pinClock.Off(); err != nil { + return err + } if (data & 1) > 0 { - t.pinData.On() + if err := t.pinData.On(); err != nil { + return err + } } else { - t.pinData.Off() + if err := t.pinData.Off(); err != nil { + return err + } } data >>= 1 - t.pinClock.On() + if err := t.pinClock.On(); err != nil { + return err + } } + + return nil } // sendData is an auxiliary function to send data to the TM1638 module -func (t *TM1638Driver) sendData(address byte, data byte) { - t.sendCommand(TM1638DataCmd | TM1638FixedAddr) - t.pinStrobe.Off() - t.send(TM1638AddrCmd | address) - t.send(data) - t.pinStrobe.On() +func (t *TM1638Driver) sendData(address byte, data byte) error { + if err := t.sendCommand(TM1638DataCmd | TM1638FixedAddr); err != nil { + return err + } + if err := t.pinStrobe.Off(); err != nil { + return err + } + if err := t.send(TM1638AddrCmd | address); err != nil { + return err + } + if err := t.send(data); err != nil { + return err + } + return t.pinStrobe.On() } // SetLED changes the color (TM1638None, TM1638Red, TM1638Green) of the specific LED -func (t *TM1638Driver) SetLED(color byte, pos byte) { +func (t *TM1638Driver) SetLED(color byte, pos byte) error { if pos > 7 { - return + return nil } - t.sendData((pos<<1)+1, color) + return t.sendData((pos<<1)+1, color) } // SetDisplay cuts and sends a byte array to the display (without dots) -func (t *TM1638Driver) SetDisplay(data []byte) { +func (t *TM1638Driver) SetDisplay(data []byte) error { minLength := int(math.Min(8, float64(len(data)))) for i := 0; i < minLength; i++ { - t.SendChar(byte(i), data[i], false) + if err := t.SendChar(byte(i), data[i], false); err != nil { + return err + } } + return nil } // SetDisplayText cuts and sends a string to the display (without dots) -func (t *TM1638Driver) SetDisplayText(text string) { +func (t *TM1638Driver) SetDisplayText(text string) error { data := t.fromStringToByteArray(text) minLength := int(math.Min(8, float64(len(data)))) for i := 0; i < minLength; i++ { - t.SendChar(byte(i), data[i], false) + if err := t.SendChar(byte(i), data[i], false); err != nil { + return err + } } + return nil } // SendChar sends one byte to the specific position in the display -func (t *TM1638Driver) SendChar(pos byte, data byte, dot bool) { +func (t *TM1638Driver) SendChar(pos byte, data byte, dot bool) error { if pos > 7 { - return + return nil } var dotData byte if dot { dotData = TM1638DispCtrl } - t.sendData(pos<<1, data|(dotData)) + return t.sendData(pos<<1, data|(dotData)) } -// fromStringToByteArray translates a string to a byte array with the corresponding representation for the 7-segment LCD, return and empty character if the font is not available +// fromStringToByteArray translates a string to a byte array with the corresponding representation +// for the 7-segment LCD, return and empty character if the font is not available func (t *TM1638Driver) fromStringToByteArray(str string) []byte { chars := strings.Split(str, "") data := make([]byte, len(chars)) diff --git a/drivers/i2c/adafruit1109_driver_test.go b/drivers/i2c/adafruit1109_driver_test.go index 9e9a1e3cf..8fcb5a94d 100644 --- a/drivers/i2c/adafruit1109_driver_test.go +++ b/drivers/i2c/adafruit1109_driver_test.go @@ -86,7 +86,7 @@ func TestAdafruit1109StartReadErr(t *testing.T) { func TestAdafruit1109Halt(t *testing.T) { d, _ := initTestAdafruit1109WithStubbedAdaptor() - d.Start() + _ = d.Start() gobottest.Assert(t, d.Halt(), nil) } @@ -116,7 +116,7 @@ func TestAdafruit1109DigitalRead(t *testing.T) { t.Run(name, func(t *testing.T) { // arrange d, a := initTestAdafruit1109WithStubbedAdaptor() - d.Start() + _ = d.Start() a.written = []byte{} // reset writes of Start() and former test // arrange reads numCallsRead := 0 @@ -149,7 +149,7 @@ func TestAdafruit1109SelectButton(t *testing.T) { t.Run(name, func(t *testing.T) { // arrange d, a := initTestAdafruit1109WithStubbedAdaptor() - d.Start() + _ = d.Start() // arrange reads numCallsRead := 0 a.i2cReadImpl = func(b []byte) (int, error) { @@ -179,7 +179,7 @@ func TestAdafruit1109UpButton(t *testing.T) { t.Run(name, func(t *testing.T) { // arrange d, a := initTestAdafruit1109WithStubbedAdaptor() - d.Start() + _ = d.Start() // arrange reads numCallsRead := 0 a.i2cReadImpl = func(b []byte) (int, error) { @@ -209,7 +209,7 @@ func TestAdafruit1109DownButton(t *testing.T) { t.Run(name, func(t *testing.T) { // arrange d, a := initTestAdafruit1109WithStubbedAdaptor() - d.Start() + _ = d.Start() // arrange reads numCallsRead := 0 a.i2cReadImpl = func(b []byte) (int, error) { @@ -239,7 +239,7 @@ func TestAdafruit1109LeftButton(t *testing.T) { t.Run(name, func(t *testing.T) { // arrange d, a := initTestAdafruit1109WithStubbedAdaptor() - d.Start() + _ = d.Start() // arrange reads numCallsRead := 0 a.i2cReadImpl = func(b []byte) (int, error) { @@ -269,7 +269,7 @@ func TestAdafruit1109RightButton(t *testing.T) { t.Run(name, func(t *testing.T) { // arrange d, a := initTestAdafruit1109WithStubbedAdaptor() - d.Start() + _ = d.Start() // arrange reads numCallsRead := 0 a.i2cReadImpl = func(b []byte) (int, error) { diff --git a/drivers/i2c/ads1x15_driver.go b/drivers/i2c/ads1x15_driver.go index 55d5ba555..1645f20ec 100644 --- a/drivers/i2c/ads1x15_driver.go +++ b/drivers/i2c/ads1x15_driver.go @@ -43,11 +43,6 @@ type ads1x15ChanCfg struct { dataRate int } -type ads1x15GainCfg struct { - bits uint16 - fullrange float64 -} - // ADS1x15Driver is the Gobot driver for the ADS1015/ADS1115 ADC // datasheet: // https://www.ti.com/lit/gpn/ads1115 diff --git a/drivers/i2c/adxl345_driver_test.go b/drivers/i2c/adxl345_driver_test.go index 69719f94a..d2f98f88c 100644 --- a/drivers/i2c/adxl345_driver_test.go +++ b/drivers/i2c/adxl345_driver_test.go @@ -75,7 +75,7 @@ func TestADXL345UseLowPower(t *testing.T) { // * set value in data rate structure // * write the data rate register (0x2C) d, a := initTestADXL345WithStubbedAdaptor() - d.Start() + _ = d.Start() a.written = []byte{} // reset writes of former test setVal := !d.bwRate.lowPower const ( @@ -97,7 +97,7 @@ func TestADXL345SetRate(t *testing.T) { // * set value in data rate structure // * write the data rate register (0x2C) d, a := initTestADXL345WithStubbedAdaptor() - d.Start() + _ = d.Start() a.written = []byte{} // reset writes of former test const ( setVal = ADXL345RateConfig(0x0F) // 3.2kHz @@ -119,7 +119,7 @@ func TestADXL345SetRange(t *testing.T) { // * set value in data format structure // * write the data format register (0x31) d, a := initTestADXL345WithStubbedAdaptor() - d.Start() + _ = d.Start() a.written = []byte{} // reset writes of former test const ( setVal = ADXL345FsRangeConfig(0x03) // +/- 16 g @@ -169,7 +169,7 @@ func TestADXL345RawXYZ(t *testing.T) { }, } d, a := initTestADXL345WithStubbedAdaptor() - d.Start() + _ = d.Start() for name, tc := range tests { t.Run(name, func(t *testing.T) { a.written = []byte{} // reset writes of former test and start @@ -198,7 +198,7 @@ func TestADXL345RawXYZ(t *testing.T) { func TestADXL345RawXYZError(t *testing.T) { // arrange d, a := initTestADXL345WithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cReadImpl = func(b []byte) (int, error) { return 0, errors.New("read error") } @@ -239,7 +239,7 @@ func TestADXL345XYZ(t *testing.T) { t.Run(name, func(t *testing.T) { // arrange d, a := initTestADXL345WithStubbedAdaptor() - d.Start() + _ = d.Start() a.written = []byte{} // reset writes of former test and start // arrange reads returnRead := append(append(tc.inputX, tc.inputY...), tc.inputZ...) @@ -262,7 +262,7 @@ func TestADXL345XYZ(t *testing.T) { func TestADXL345XYZError(t *testing.T) { // arrange d, a := initTestADXL345WithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cReadImpl = func(b []byte) (int, error) { return 0, errors.New("read error") } @@ -307,7 +307,7 @@ func TestADXL345_shutdown(t *testing.T) { // * reset the measurement bit in structure // * write the power control register (0x2D) d, a := initTestADXL345WithStubbedAdaptor() - d.Start() + _ = d.Start() a.written = []byte{} // reset writes of former test const ( wantReg = uint8(0x2D) diff --git a/drivers/i2c/bme280_driver.go b/drivers/i2c/bme280_driver.go index bcb3bf0be..a42a1851c 100644 --- a/drivers/i2c/bme280_driver.go +++ b/drivers/i2c/bme280_driver.go @@ -135,7 +135,7 @@ func (d *BME280Driver) Humidity() (humidity float32, err error) { return } -func (d *BME280Driver) initializationBME280() (err error) { +func (d *BME280Driver) initializationBME280() error { // call the initialization routine of base class BMP280Driver, which do: // * initializes temperature and pressure calibration coefficients // * set the control register @@ -152,13 +152,15 @@ func (d *BME280Driver) initializationBME280() (err error) { } // read the humidity calibration coefficients. -func (d *BME280Driver) initHumidity() (err error) { - var hch1 byte - if hch1, err = d.connection.ReadByteData(bme280RegCalibDigH1); err != nil { +func (d *BME280Driver) initHumidity() error { + hch1, err := d.connection.ReadByteData(bme280RegCalibDigH1) + if err != nil { return err } buf := bytes.NewBuffer([]byte{hch1}) - binary.Read(buf, binary.BigEndian, &d.humCalCoeffs.h1) + if err := binary.Read(buf, binary.BigEndian, &d.humCalCoeffs.h1); err != nil { + return err + } coefficients := make([]byte, 7) if err = d.connection.ReadBlockData(bme280RegCalibDigH2LSB, coefficients); err != nil { @@ -170,13 +172,30 @@ func (d *BME280Driver) initHumidity() (err error) { var addrE4 byte var addrE5 byte var addrE6 byte - - binary.Read(buf, binary.LittleEndian, &d.humCalCoeffs.h2) // E1 ... - binary.Read(buf, binary.BigEndian, &d.humCalCoeffs.h3) // E3 - binary.Read(buf, binary.BigEndian, &addrE4) // E4 - binary.Read(buf, binary.BigEndian, &addrE5) // E5 - binary.Read(buf, binary.BigEndian, &addrE6) // E6 - binary.Read(buf, binary.BigEndian, &d.humCalCoeffs.h6) // ... E7 + // E1 ... + if err := binary.Read(buf, binary.LittleEndian, &d.humCalCoeffs.h2); err != nil { + return err + } + // E3 + if err := binary.Read(buf, binary.BigEndian, &d.humCalCoeffs.h3); err != nil { + return err + } + // E4 + if err := binary.Read(buf, binary.BigEndian, &addrE4); err != nil { + return err + } + // E5 + if err := binary.Read(buf, binary.BigEndian, &addrE5); err != nil { + return err + } + // E6 + if err := binary.Read(buf, binary.BigEndian, &addrE6); err != nil { + return err + } + // ... E7 + if err := binary.Read(buf, binary.BigEndian, &d.humCalCoeffs.h6); err != nil { + return err + } d.humCalCoeffs.h4 = 0 + (int16(addrE4) << 4) | (int16(addrE5 & 0x0F)) d.humCalCoeffs.h5 = 0 + (int16(addrE6) << 4) | (int16(addrE5) >> 4) @@ -184,14 +203,17 @@ func (d *BME280Driver) initHumidity() (err error) { // The 'ctrl_hum' register (0xF2) sets the humidity data acquisition options of // the device. Changes to this register only become effective after a write // operation to 'ctrl_meas' (0xF4). So we read the current value in, then write it back - d.connection.WriteByteData(bme280RegControlHumidity, uint8(d.ctrlHumOversamp)) + if err := d.connection.WriteByteData(bme280RegControlHumidity, uint8(d.ctrlHumOversamp)); err != nil { + return err + } - var cmr uint8 - cmr, err = d.connection.ReadByteData(bmp280RegCtrl) - if err == nil { - err = d.connection.WriteByteData(bmp280RegCtrl, cmr) + cmr, err := d.connection.ReadByteData(bmp280RegCtrl) + if err != nil { + return err } - return err + + return d.connection.WriteByteData(bmp280RegCtrl, cmr) + } func (d *BME280Driver) rawHumidity() (uint32, error) { @@ -204,7 +226,9 @@ func (d *BME280Driver) rawHumidity() (uint32, error) { } buf := bytes.NewBuffer(ret) var rawH uint16 - binary.Read(buf, binary.BigEndian, &rawH) + if err := binary.Read(buf, binary.BigEndian, &rawH); err != nil { + return 0, err + } return uint32(rawH), nil } diff --git a/drivers/i2c/bme280_driver_test.go b/drivers/i2c/bme280_driver_test.go index f90f8a23f..80635ac87 100644 --- a/drivers/i2c/bme280_driver_test.go +++ b/drivers/i2c/bme280_driver_test.go @@ -70,7 +70,7 @@ func TestBME280Measurements(t *testing.T) { copy(b, buf.Bytes()) return buf.Len(), nil } - bme280.Start() + _ = bme280.Start() hum, err := bme280.Humidity() gobottest.Assert(t, err, nil) gobottest.Assert(t, hum, float32(51.20179)) @@ -116,7 +116,7 @@ func TestBME280InitH2Error(t *testing.T) { func TestBME280HumidityWriteError(t *testing.T) { bme280, adaptor := initTestBME280WithStubbedAdaptor() - bme280.Start() + _ = bme280.Start() adaptor.i2cWriteImpl = func([]byte) (int, error) { return 0, errors.New("write error") @@ -128,7 +128,7 @@ func TestBME280HumidityWriteError(t *testing.T) { func TestBME280HumidityReadError(t *testing.T) { bme280, adaptor := initTestBME280WithStubbedAdaptor() - bme280.Start() + _ = bme280.Start() adaptor.i2cReadImpl = func([]byte) (int, error) { return 0, errors.New("read error") @@ -157,7 +157,7 @@ func TestBME280HumidityNotEnabled(t *testing.T) { copy(b, buf.Bytes()) return buf.Len(), nil } - bme280.Start() + _ = bme280.Start() hum, err := bme280.Humidity() gobottest.Assert(t, err, errors.New("Humidity disabled")) gobottest.Assert(t, hum, float32(0.0)) diff --git a/drivers/i2c/bmp180_driver.go b/drivers/i2c/bmp180_driver.go index 545854cd3..2d52a063e 100644 --- a/drivers/i2c/bmp180_driver.go +++ b/drivers/i2c/bmp180_driver.go @@ -59,12 +59,13 @@ type BMP180Driver struct { // NewBMP180Driver creates a new driver with the i2c interface for the BMP180 device. // Params: -// conn Connector - the Adaptor to use with this Driver +// +// conn Connector - the Adaptor to use with this Driver // // Optional params: -// i2c.WithBus(int): bus to use with this driver -// i2c.WithAddress(int): address to use with this driver // +// i2c.WithBus(int): bus to use with this driver +// i2c.WithAddress(int): address to use with this driver func NewBMP180Driver(c Connector, options ...func(Config)) *BMP180Driver { d := &BMP180Driver{ Driver: NewDriver(c, "BMP180", bmp180DefaultAddress), @@ -121,26 +122,45 @@ func (d *BMP180Driver) Pressure() (pressure float32, err error) { return d.calculatePressure(rawTemp, rawPressure, d.oversampling), nil } -func (d *BMP180Driver) initialization() (err error) { +func (d *BMP180Driver) initialization() error { // read the 11 calibration coefficients. coefficients := make([]byte, 22) - if err = d.connection.ReadBlockData(bmp180RegisterAC1MSB, coefficients); err != nil { + if err := d.connection.ReadBlockData(bmp180RegisterAC1MSB, coefficients); err != nil { return err } buf := bytes.NewBuffer(coefficients) - binary.Read(buf, binary.BigEndian, &d.calCoeffs.ac1) - binary.Read(buf, binary.BigEndian, &d.calCoeffs.ac2) - binary.Read(buf, binary.BigEndian, &d.calCoeffs.ac3) - binary.Read(buf, binary.BigEndian, &d.calCoeffs.ac4) - binary.Read(buf, binary.BigEndian, &d.calCoeffs.ac5) - binary.Read(buf, binary.BigEndian, &d.calCoeffs.ac6) - binary.Read(buf, binary.BigEndian, &d.calCoeffs.b1) - binary.Read(buf, binary.BigEndian, &d.calCoeffs.b2) - binary.Read(buf, binary.BigEndian, &d.calCoeffs.mb) - binary.Read(buf, binary.BigEndian, &d.calCoeffs.mc) - binary.Read(buf, binary.BigEndian, &d.calCoeffs.md) - - return nil + if err := binary.Read(buf, binary.BigEndian, &d.calCoeffs.ac1); err != nil { + return err + } + if err := binary.Read(buf, binary.BigEndian, &d.calCoeffs.ac2); err != nil { + return err + } + if err := binary.Read(buf, binary.BigEndian, &d.calCoeffs.ac3); err != nil { + return err + } + if err := binary.Read(buf, binary.BigEndian, &d.calCoeffs.ac4); err != nil { + return err + } + if err := binary.Read(buf, binary.BigEndian, &d.calCoeffs.ac5); err != nil { + return err + } + if err := binary.Read(buf, binary.BigEndian, &d.calCoeffs.ac6); err != nil { + return err + } + if err := binary.Read(buf, binary.BigEndian, &d.calCoeffs.b1); err != nil { + return err + } + if err := binary.Read(buf, binary.BigEndian, &d.calCoeffs.b2); err != nil { + return err + } + if err := binary.Read(buf, binary.BigEndian, &d.calCoeffs.mb); err != nil { + return err + } + if err := binary.Read(buf, binary.BigEndian, &d.calCoeffs.mc); err != nil { + return err + } + return binary.Read(buf, binary.BigEndian, &d.calCoeffs.md) + } func (d *BMP180Driver) rawTemp() (int16, error) { @@ -155,7 +175,9 @@ func (d *BMP180Driver) rawTemp() (int16, error) { } buf := bytes.NewBuffer(ret) var rawTemp int16 - binary.Read(buf, binary.BigEndian, &rawTemp) + if err := binary.Read(buf, binary.BigEndian, &rawTemp); err != nil { + return 0, err + } return rawTemp, nil } diff --git a/drivers/i2c/bmp180_driver_test.go b/drivers/i2c/bmp180_driver_test.go index 882c07a7a..87dfcfca6 100644 --- a/drivers/i2c/bmp180_driver_test.go +++ b/drivers/i2c/bmp180_driver_test.go @@ -49,28 +49,28 @@ func TestBMP180Measurements(t *testing.T) { buf := new(bytes.Buffer) // Values from the datasheet example. if adaptor.written[len(adaptor.written)-1] == bmp180RegisterAC1MSB { - binary.Write(buf, binary.BigEndian, int16(408)) - binary.Write(buf, binary.BigEndian, int16(-72)) - binary.Write(buf, binary.BigEndian, int16(-14383)) - binary.Write(buf, binary.BigEndian, uint16(32741)) - binary.Write(buf, binary.BigEndian, uint16(32757)) - binary.Write(buf, binary.BigEndian, uint16(23153)) - binary.Write(buf, binary.BigEndian, int16(6190)) - binary.Write(buf, binary.BigEndian, int16(4)) - binary.Write(buf, binary.BigEndian, int16(-32768)) - binary.Write(buf, binary.BigEndian, int16(-8711)) - binary.Write(buf, binary.BigEndian, int16(2868)) + _ = binary.Write(buf, binary.BigEndian, int16(408)) + _ = binary.Write(buf, binary.BigEndian, int16(-72)) + _ = binary.Write(buf, binary.BigEndian, int16(-14383)) + _ = binary.Write(buf, binary.BigEndian, uint16(32741)) + _ = binary.Write(buf, binary.BigEndian, uint16(32757)) + _ = binary.Write(buf, binary.BigEndian, uint16(23153)) + _ = binary.Write(buf, binary.BigEndian, int16(6190)) + _ = binary.Write(buf, binary.BigEndian, int16(4)) + _ = binary.Write(buf, binary.BigEndian, int16(-32768)) + _ = binary.Write(buf, binary.BigEndian, int16(-8711)) + _ = binary.Write(buf, binary.BigEndian, int16(2868)) } else if adaptor.written[len(adaptor.written)-2] == bmp180CtlTemp && adaptor.written[len(adaptor.written)-1] == bmp180RegisterDataMSB { - binary.Write(buf, binary.BigEndian, int16(27898)) + _ = binary.Write(buf, binary.BigEndian, int16(27898)) } else if adaptor.written[len(adaptor.written)-2] == bmp180CtlPressure && adaptor.written[len(adaptor.written)-1] == bmp180RegisterDataMSB { - binary.Write(buf, binary.BigEndian, int16(23843)) + _ = binary.Write(buf, binary.BigEndian, int16(23843)) // XLSB, not used in this test. buf.WriteByte(0) } copy(b, buf.Bytes()) return buf.Len(), nil } - bmp180.Start() + _ = bmp180.Start() temp, err := bmp180.Temperature() gobottest.Assert(t, err, nil) gobottest.Assert(t, temp, float32(15.0)) @@ -85,28 +85,28 @@ func TestBMP180TemperatureError(t *testing.T) { buf := new(bytes.Buffer) // Values from the datasheet example. if adaptor.written[len(adaptor.written)-1] == bmp180RegisterAC1MSB { - binary.Write(buf, binary.BigEndian, int16(408)) - binary.Write(buf, binary.BigEndian, int16(-72)) - binary.Write(buf, binary.BigEndian, int16(-14383)) - binary.Write(buf, binary.BigEndian, uint16(32741)) - binary.Write(buf, binary.BigEndian, uint16(32757)) - binary.Write(buf, binary.BigEndian, uint16(23153)) - binary.Write(buf, binary.BigEndian, int16(6190)) - binary.Write(buf, binary.BigEndian, int16(4)) - binary.Write(buf, binary.BigEndian, int16(-32768)) - binary.Write(buf, binary.BigEndian, int16(-8711)) - binary.Write(buf, binary.BigEndian, int16(2868)) + _ = binary.Write(buf, binary.BigEndian, int16(408)) + _ = binary.Write(buf, binary.BigEndian, int16(-72)) + _ = binary.Write(buf, binary.BigEndian, int16(-14383)) + _ = binary.Write(buf, binary.BigEndian, uint16(32741)) + _ = binary.Write(buf, binary.BigEndian, uint16(32757)) + _ = binary.Write(buf, binary.BigEndian, uint16(23153)) + _ = binary.Write(buf, binary.BigEndian, int16(6190)) + _ = binary.Write(buf, binary.BigEndian, int16(4)) + _ = binary.Write(buf, binary.BigEndian, int16(-32768)) + _ = binary.Write(buf, binary.BigEndian, int16(-8711)) + _ = binary.Write(buf, binary.BigEndian, int16(2868)) } else if adaptor.written[len(adaptor.written)-2] == bmp180CtlTemp && adaptor.written[len(adaptor.written)-1] == bmp180RegisterDataMSB { return 0, errors.New("temp error") } else if adaptor.written[len(adaptor.written)-2] == bmp180CtlPressure && adaptor.written[len(adaptor.written)-1] == bmp180RegisterDataMSB { - binary.Write(buf, binary.BigEndian, int16(23843)) + _ = binary.Write(buf, binary.BigEndian, int16(23843)) // XLSB, not used in this test. buf.WriteByte(0) } copy(b, buf.Bytes()) return buf.Len(), nil } - bmp180.Start() + _ = bmp180.Start() _, err := bmp180.Temperature() gobottest.Assert(t, err, errors.New("temp error")) } @@ -117,33 +117,33 @@ func TestBMP180PressureError(t *testing.T) { buf := new(bytes.Buffer) // Values from the datasheet example. if adaptor.written[len(adaptor.written)-1] == bmp180RegisterAC1MSB { - binary.Write(buf, binary.BigEndian, int16(408)) - binary.Write(buf, binary.BigEndian, int16(-72)) - binary.Write(buf, binary.BigEndian, int16(-14383)) - binary.Write(buf, binary.BigEndian, uint16(32741)) - binary.Write(buf, binary.BigEndian, uint16(32757)) - binary.Write(buf, binary.BigEndian, uint16(23153)) - binary.Write(buf, binary.BigEndian, int16(6190)) - binary.Write(buf, binary.BigEndian, int16(4)) - binary.Write(buf, binary.BigEndian, int16(-32768)) - binary.Write(buf, binary.BigEndian, int16(-8711)) - binary.Write(buf, binary.BigEndian, int16(2868)) + _ = binary.Write(buf, binary.BigEndian, int16(408)) + _ = binary.Write(buf, binary.BigEndian, int16(-72)) + _ = binary.Write(buf, binary.BigEndian, int16(-14383)) + _ = binary.Write(buf, binary.BigEndian, uint16(32741)) + _ = binary.Write(buf, binary.BigEndian, uint16(32757)) + _ = binary.Write(buf, binary.BigEndian, uint16(23153)) + _ = binary.Write(buf, binary.BigEndian, int16(6190)) + _ = binary.Write(buf, binary.BigEndian, int16(4)) + _ = binary.Write(buf, binary.BigEndian, int16(-32768)) + _ = binary.Write(buf, binary.BigEndian, int16(-8711)) + _ = binary.Write(buf, binary.BigEndian, int16(2868)) } else if adaptor.written[len(adaptor.written)-2] == bmp180CtlTemp && adaptor.written[len(adaptor.written)-1] == bmp180RegisterDataMSB { - binary.Write(buf, binary.BigEndian, int16(27898)) + _ = binary.Write(buf, binary.BigEndian, int16(27898)) } else if adaptor.written[len(adaptor.written)-2] == bmp180CtlPressure && adaptor.written[len(adaptor.written)-1] == bmp180RegisterDataMSB { return 0, errors.New("press error") } copy(b, buf.Bytes()) return buf.Len(), nil } - bmp180.Start() + _ = bmp180.Start() _, err := bmp180.Pressure() gobottest.Assert(t, err, errors.New("press error")) } func TestBMP180PressureWriteError(t *testing.T) { bmp180, adaptor := initTestBMP180WithStubbedAdaptor() - bmp180.Start() + _ = bmp180.Start() adaptor.i2cWriteImpl = func([]byte) (int, error) { return 0, errors.New("write error") diff --git a/drivers/i2c/bmp280_driver.go b/drivers/i2c/bmp280_driver.go index 73486fa04..cea919de4 100644 --- a/drivers/i2c/bmp280_driver.go +++ b/drivers/i2c/bmp280_driver.go @@ -96,12 +96,13 @@ type BMP280Driver struct { // NewBMP280Driver creates a new driver with specified i2c interface. // Params: -// c Connector - the Adaptor to use with this Driver +// +// c Connector - the Adaptor to use with this Driver // // Optional params: -// i2c.WithBus(int): bus to use with this driver -// i2c.WithAddress(int): address to use with this driver // +// i2c.WithBus(int): bus to use with this driver +// i2c.WithAddress(int): address to use with this driver func NewBMP280Driver(c Connector, options ...func(Config)) *BMP280Driver { d := &BMP280Driver{ Driver: NewDriver(c, "BMP280", bmp280DefaultAddress), @@ -190,7 +191,8 @@ func (d *BMP280Driver) Pressure() (press float32, err error) { // Altitude returns the current altitude in meters based on the // current barometric pressure and estimated pressure at sea level. // Calculation is based on code from Adafruit BME280 library -// https://github.com/adafruit/Adafruit_BME280_Library +// +// https://github.com/adafruit/Adafruit_BME280_Library func (d *BMP280Driver) Altitude() (alt float32, err error) { atmP, _ := d.Pressure() atmP /= 100.0 @@ -200,66 +202,98 @@ func (d *BMP280Driver) Altitude() (alt float32, err error) { } // initialization reads the calibration coefficients. -func (d *BMP280Driver) initialization() (err error) { +func (d *BMP280Driver) initialization() error { coefficients := make([]byte, 24) - if err = d.connection.ReadBlockData(bmp280RegCalib00, coefficients); err != nil { + if err := d.connection.ReadBlockData(bmp280RegCalib00, coefficients); err != nil { return err } buf := bytes.NewBuffer(coefficients) - binary.Read(buf, binary.LittleEndian, &d.calCoeffs.t1) - binary.Read(buf, binary.LittleEndian, &d.calCoeffs.t2) - binary.Read(buf, binary.LittleEndian, &d.calCoeffs.t3) - binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p1) - binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p2) - binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p3) - binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p4) - binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p5) - binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p6) - binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p7) - binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p8) - binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p9) + if err := binary.Read(buf, binary.LittleEndian, &d.calCoeffs.t1); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &d.calCoeffs.t2); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &d.calCoeffs.t3); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p1); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p2); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p3); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p4); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p5); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p6); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p7); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p8); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &d.calCoeffs.p9); err != nil { + return err + } ctrlReg := uint8(d.ctrlPwrMode) | uint8(d.ctrlPressOversamp)<<2 | uint8(d.ctrlTempOversamp)<<5 - d.connection.WriteByteData(bmp280RegCtrl, ctrlReg) + if err := d.connection.WriteByteData(bmp280RegCtrl, ctrlReg); err != nil { + return err + } confReg := uint8(bmp280ConfStandBy0005)<<2 | uint8(d.confFilter)<<5 - d.connection.WriteByteData(bmp280RegConf, confReg & ^uint8(bmp280ConfSPIBit)) - - return nil + return d.connection.WriteByteData(bmp280RegConf, confReg & ^uint8(bmp280ConfSPIBit)) } -func (d *BMP280Driver) rawTemp() (temp int32, err error) { +func (d *BMP280Driver) rawTemp() (int32, error) { var tp0, tp1, tp2 byte data := make([]byte, 3) - if err = d.connection.ReadBlockData(bmp280RegTempData, data); err != nil { + if err := d.connection.ReadBlockData(bmp280RegTempData, data); err != nil { return 0, err } buf := bytes.NewBuffer(data) - binary.Read(buf, binary.LittleEndian, &tp0) - binary.Read(buf, binary.LittleEndian, &tp1) - binary.Read(buf, binary.LittleEndian, &tp2) - - temp = ((int32(tp2) >> 4) | (int32(tp1) << 4) | (int32(tp0) << 12)) + if err := binary.Read(buf, binary.LittleEndian, &tp0); err != nil { + return 0, err + } + if err := binary.Read(buf, binary.LittleEndian, &tp1); err != nil { + return 0, err + } + if err := binary.Read(buf, binary.LittleEndian, &tp2); err != nil { + return 0, err + } - return + return ((int32(tp2) >> 4) | (int32(tp1) << 4) | (int32(tp0) << 12)), nil } -func (d *BMP280Driver) rawPressure() (press int32, err error) { +func (d *BMP280Driver) rawPressure() (int32, error) { var tp0, tp1, tp2 byte data := make([]byte, 3) - if err = d.connection.ReadBlockData(bmp280RegPressureData, data); err != nil { + if err := d.connection.ReadBlockData(bmp280RegPressureData, data); err != nil { return 0, err } buf := bytes.NewBuffer(data) - binary.Read(buf, binary.LittleEndian, &tp0) - binary.Read(buf, binary.LittleEndian, &tp1) - binary.Read(buf, binary.LittleEndian, &tp2) - - press = ((int32(tp2) >> 4) | (int32(tp1) << 4) | (int32(tp0) << 12)) + if err := binary.Read(buf, binary.LittleEndian, &tp0); err != nil { + return 0, err + } + if err := binary.Read(buf, binary.LittleEndian, &tp1); err != nil { + return 0, err + } + if err := binary.Read(buf, binary.LittleEndian, &tp2); err != nil { + return 0, err + } - return + return ((int32(tp2) >> 4) | (int32(tp1) << 4) | (int32(tp0) << 12)), nil } func (d *BMP280Driver) calculateTemp(rawTemp int32) (float32, int32) { diff --git a/drivers/i2c/bmp280_driver_test.go b/drivers/i2c/bmp280_driver_test.go index e312f1822..bbbe13c8c 100644 --- a/drivers/i2c/bmp280_driver_test.go +++ b/drivers/i2c/bmp280_driver_test.go @@ -86,7 +86,7 @@ func TestBMP280Measurements(t *testing.T) { copy(b, buf.Bytes()) return buf.Len(), nil } - d.Start() + _ = d.Start() temp, err := d.Temperature() gobottest.Assert(t, err, nil) gobottest.Assert(t, temp, float32(25.014637)) @@ -100,7 +100,7 @@ func TestBMP280Measurements(t *testing.T) { func TestBMP280TemperatureWriteError(t *testing.T) { d, adaptor := initTestBMP280WithStubbedAdaptor() - d.Start() + _ = d.Start() adaptor.i2cWriteImpl = func([]byte) (int, error) { return 0, errors.New("write error") @@ -112,7 +112,7 @@ func TestBMP280TemperatureWriteError(t *testing.T) { func TestBMP280TemperatureReadError(t *testing.T) { d, adaptor := initTestBMP280WithStubbedAdaptor() - d.Start() + _ = d.Start() adaptor.i2cReadImpl = func([]byte) (int, error) { return 0, errors.New("read error") @@ -124,7 +124,7 @@ func TestBMP280TemperatureReadError(t *testing.T) { func TestBMP280PressureWriteError(t *testing.T) { d, adaptor := initTestBMP280WithStubbedAdaptor() - d.Start() + _ = d.Start() adaptor.i2cWriteImpl = func([]byte) (int, error) { return 0, errors.New("write error") @@ -136,7 +136,7 @@ func TestBMP280PressureWriteError(t *testing.T) { func TestBMP280PressureReadError(t *testing.T) { d, adaptor := initTestBMP280WithStubbedAdaptor() - d.Start() + _ = d.Start() adaptor.i2cReadImpl = func([]byte) (int, error) { return 0, errors.New("read error") diff --git a/drivers/i2c/bmp388_driver.go b/drivers/i2c/bmp388_driver.go index 612cbd91e..d7bf2f30b 100644 --- a/drivers/i2c/bmp388_driver.go +++ b/drivers/i2c/bmp388_driver.go @@ -93,12 +93,13 @@ type BMP388Driver struct { // NewBMP388Driver creates a new driver with specified i2c interface. // Params: -// c Connector - the Adaptor to use with this Driver +// +// c Connector - the Adaptor to use with this Driver // // Optional params: -// i2c.WithBus(int): bus to use with this driver -// i2c.WithAddress(int): address to use with this driver // +// i2c.WithBus(int): bus to use with this driver +// i2c.WithAddress(int): address to use with this driver func NewBMP388Driver(c Connector, options ...func(Config)) *BMP388Driver { d := &BMP388Driver{ Driver: NewDriver(c, "BMP388", bmp388DefaultAddress), @@ -192,9 +193,10 @@ func (d *BMP388Driver) Altitude(accuracy BMP388Accuracy) (alt float32, err error } // initialization reads the calibration coefficients. -func (d *BMP388Driver) initialization() (err error) { - var chipID uint8 - if chipID, err = d.connection.ReadByteData(bmp388RegChipID); err != nil { +func (d *BMP388Driver) initialization() error { + + chipID, err := d.connection.ReadByteData(bmp388RegChipID) + if err != nil { return err } @@ -225,20 +227,48 @@ func (d *BMP388Driver) initialization() (err error) { } buf := bytes.NewBuffer(coefficients) - binary.Read(buf, binary.LittleEndian, &t1) - binary.Read(buf, binary.LittleEndian, &t2) - binary.Read(buf, binary.LittleEndian, &t3) - binary.Read(buf, binary.LittleEndian, &p1) - binary.Read(buf, binary.LittleEndian, &p2) - binary.Read(buf, binary.LittleEndian, &p3) - binary.Read(buf, binary.LittleEndian, &p4) - binary.Read(buf, binary.LittleEndian, &p5) - binary.Read(buf, binary.LittleEndian, &p6) - binary.Read(buf, binary.LittleEndian, &p7) - binary.Read(buf, binary.LittleEndian, &p8) - binary.Read(buf, binary.LittleEndian, &p9) - binary.Read(buf, binary.LittleEndian, &p10) - binary.Read(buf, binary.LittleEndian, &p11) + if err := binary.Read(buf, binary.LittleEndian, &t1); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &t2); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &t3); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &p1); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &p2); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &p3); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &p4); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &p5); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &p6); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &p7); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &p8); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &p9); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &p10); err != nil { + return err + } + if err := binary.Read(buf, binary.LittleEndian, &p11); err != nil { + return err + } d.calCoeffs.t1 = float32(float64(t1) / math.Pow(2, -8)) d.calCoeffs.t2 = float32(float64(t2) / math.Pow(2, 30)) @@ -255,50 +285,59 @@ func (d *BMP388Driver) initialization() (err error) { d.calCoeffs.p10 = float32(float64(p10) / math.Pow(2, 48)) d.calCoeffs.p11 = float32(float64(p11) / math.Pow(2, 65)) - if err = d.connection.WriteByteData(bmp388RegCMD, bmp388CMDSoftReset); err != nil { + if err := d.connection.WriteByteData(bmp388RegCMD, bmp388CMDSoftReset); err != nil { return err } - if err = d.connection.WriteByteData(bmp388RegConf, uint8(d.confFilter)<<1); err != nil { - return err - } - - return nil + return d.connection.WriteByteData(bmp388RegConf, uint8(d.confFilter)<<1) } -func (d *BMP388Driver) rawTemp() (temp int32, err error) { +func (d *BMP388Driver) rawTemp() (int32, error) { var tp0, tp1, tp2 byte data := make([]byte, 3) - if err = d.connection.ReadBlockData(bmp388RegTempData, data); err != nil { + if err := d.connection.ReadBlockData(bmp388RegTempData, data); err != nil { return 0, err } buf := bytes.NewBuffer(data) + // XLSB + if err := binary.Read(buf, binary.LittleEndian, &tp0); err != nil { + return 0, err + } + // LSB + if err := binary.Read(buf, binary.LittleEndian, &tp1); err != nil { + return 0, err + } + // MSB + if err := binary.Read(buf, binary.LittleEndian, &tp2); err != nil { + return 0, err + } - binary.Read(buf, binary.LittleEndian, &tp0) // XLSB - binary.Read(buf, binary.LittleEndian, &tp1) // LSB - binary.Read(buf, binary.LittleEndian, &tp2) // MSB - - temp = ((int32(tp2) << 16) | (int32(tp1) << 8) | int32(tp0)) - return + return ((int32(tp2) << 16) | (int32(tp1) << 8) | int32(tp0)), nil } -func (d *BMP388Driver) rawPressure() (press int32, err error) { +func (d *BMP388Driver) rawPressure() (int32, error) { var tp0, tp1, tp2 byte data := make([]byte, 3) - if err = d.connection.ReadBlockData(bmp388RegPressureData, data); err != nil { + if err := d.connection.ReadBlockData(bmp388RegPressureData, data); err != nil { return 0, err } buf := bytes.NewBuffer(data) + // XLSB + if err := binary.Read(buf, binary.LittleEndian, &tp0); err != nil { + return 0, err + } + // LSB + if err := binary.Read(buf, binary.LittleEndian, &tp1); err != nil { + return 0, err + } + // MSB + if err := binary.Read(buf, binary.LittleEndian, &tp2); err != nil { + return 0, err + } - binary.Read(buf, binary.LittleEndian, &tp0) // XLSB - binary.Read(buf, binary.LittleEndian, &tp1) // LSB - binary.Read(buf, binary.LittleEndian, &tp2) // MSB - - press = ((int32(tp2) << 16) | (int32(tp1) << 8) | int32(tp0)) - - return + return ((int32(tp2) << 16) | (int32(tp1) << 8) | int32(tp0)), nil } func (d *BMP388Driver) calculateTemp(rawTemp int32) float32 { diff --git a/drivers/i2c/bmp388_driver_test.go b/drivers/i2c/bmp388_driver_test.go index 7f273a975..fb0ce1b59 100644 --- a/drivers/i2c/bmp388_driver_test.go +++ b/drivers/i2c/bmp388_driver_test.go @@ -25,7 +25,7 @@ func initTestBMP388WithStubbedAdaptor() (*BMP388Driver, *i2cTestAdaptor) { buf := new(bytes.Buffer) // Simulate returning of 0x50 for the // ReadByteData(bmp388RegChipID) call in initialisation() - binary.Write(buf, binary.LittleEndian, uint8(0x50)) + _ = binary.Write(buf, binary.LittleEndian, uint8(0x50)) copy(b, buf.Bytes()) return buf.Len(), nil } @@ -69,7 +69,7 @@ func TestBMP388Measurements(t *testing.T) { case bmp388RegChipID: // Simulate returning of 0x50 for the // ReadByteData(bmp388RegChipID) call in initialisation() - binary.Write(buf, binary.LittleEndian, uint8(0x50)) + _ = binary.Write(buf, binary.LittleEndian, uint8(0x50)) case bmp388RegCalib00: // Values produced by dumping data from actual sensor buf.Write([]byte{36, 107, 156, 73, 246, 104, 255, 189, 245, 35, 0, 151, 101, 184, 122, 243, 246, 211, 64, 14, 196, 0, 0, 0}) @@ -82,7 +82,7 @@ func TestBMP388Measurements(t *testing.T) { copy(b, buf.Bytes()) return buf.Len(), nil } - d.Start() + _ = d.Start() temp, err := d.Temperature(2) gobottest.Assert(t, err, nil) gobottest.Assert(t, temp, float32(22.906143)) @@ -96,7 +96,7 @@ func TestBMP388Measurements(t *testing.T) { func TestBMP388TemperatureWriteError(t *testing.T) { d, a := initTestBMP388WithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cWriteImpl = func([]byte) (int, error) { return 0, errors.New("write error") @@ -108,7 +108,7 @@ func TestBMP388TemperatureWriteError(t *testing.T) { func TestBMP388TemperatureReadError(t *testing.T) { d, a := initTestBMP388WithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cReadImpl = func([]byte) (int, error) { return 0, errors.New("read error") @@ -120,7 +120,7 @@ func TestBMP388TemperatureReadError(t *testing.T) { func TestBMP388PressureWriteError(t *testing.T) { d, a := initTestBMP388WithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cWriteImpl = func([]byte) (int, error) { return 0, errors.New("write error") @@ -132,7 +132,7 @@ func TestBMP388PressureWriteError(t *testing.T) { func TestBMP388PressureReadError(t *testing.T) { d, a := initTestBMP388WithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cReadImpl = func([]byte) (int, error) { return 0, errors.New("read error") diff --git a/drivers/i2c/ccs811_driver.go b/drivers/i2c/ccs811_driver.go index 1d48f58f8..1d50e6b4f 100644 --- a/drivers/i2c/ccs811_driver.go +++ b/drivers/i2c/ccs811_driver.go @@ -31,9 +31,9 @@ const ( //This multi-byte read only register contains the calculated eCO2 (ppm) and eTVOC (ppb) values followed by the STATUS register, ERROR_ID register and the RAW_DATA register. ccs811RegAlgResultData = 0x02 //Two byte read only register which contains the latest readings from the sensor. - ccs811RegRawData = 0x03 + //ccs811RegRawData = 0x03 //A multi-byte register that can be written with the current Humidity and Temperature values if known. - ccs811RegEnvData = 0x05 + //ccs811RegEnvData = 0x05 //Register that holds the NTC value used for temperature calcualtions ccs811RegNtc = 0x06 //Asserting the SW_RESET will restart the CCS811 in Boot mode to enable new application firmware to be downloaded. @@ -72,7 +72,7 @@ type CCS811Status struct { FwMode byte } -//NewCCS811Status returns a new instance of the package ccs811 status definition +// NewCCS811Status returns a new instance of the package ccs811 status definition func NewCCS811Status(data uint8) *CCS811Status { return &CCS811Status{ HasError: data & 0x01, @@ -82,9 +82,9 @@ func NewCCS811Status(data uint8) *CCS811Status { } } -//CCS811MeasMode represents the current measurement configuration. -//The following definitions were taken from the bit fields of the ccs811RegMeasMode defined in -//https://ams.com/documents/20143/36005/CCS811_DS000459_6-00.pdf/c7091525-c7e5-37ac-eedb-b6c6828b0dcf#page=16 +// CCS811MeasMode represents the current measurement configuration. +// The following definitions were taken from the bit fields of the ccs811RegMeasMode defined in +// https://ams.com/documents/20143/36005/CCS811_DS000459_6-00.pdf/c7091525-c7e5-37ac-eedb-b6c6828b0dcf#page=16 type CCS811MeasMode struct { //If intThresh is 1 a data measurement will only be taken when the sensor value meets the threshold constraint. //The threshold value is set in the threshold register (0x10) @@ -95,8 +95,8 @@ type CCS811MeasMode struct { driveMode CCS811DriveMode } -//NewCCS811MeasMode returns a new instance of the package ccs811 measurement mode configuration. This represents the desired initial -//state of the measurement mode register. +// NewCCS811MeasMode returns a new instance of the package ccs811 measurement mode configuration. This represents the desired initial +// state of the measurement mode register. func NewCCS811MeasMode() *CCS811MeasMode { return &CCS811MeasMode{ // Disable this by default as this library does not contain the functionality to use the internal interrupt feature. @@ -111,14 +111,14 @@ func (mm *CCS811MeasMode) GetMeasMode() byte { return (mm.intThresh << 2) | (mm.intDataRdy << 3) | uint8((mm.driveMode << 4)) } -//CCS811Driver is the Gobot driver for the CCS811 (air quality sensor) Adafruit breakout board +// CCS811Driver is the Gobot driver for the CCS811 (air quality sensor) Adafruit breakout board type CCS811Driver struct { *Driver measMode *CCS811MeasMode ntcResistanceValue uint32 } -//NewCCS811Driver creates a new driver for the CCS811 (air quality sensor) +// NewCCS811Driver creates a new driver for the CCS811 (air quality sensor) func NewCCS811Driver(c Connector, options ...func(Config)) *CCS811Driver { d := &CCS811Driver{ Driver: NewDriver(c, "CCS811", ccs811DefaultAddress), @@ -135,7 +135,7 @@ func NewCCS811Driver(c Connector, options ...func(Config)) *CCS811Driver { return d } -//WithCCS811MeasMode sets the sampling rate of the device +// WithCCS811MeasMode sets the sampling rate of the device func WithCCS811MeasMode(mode CCS811DriveMode) func(Config) { return func(c Config) { d, _ := c.(*CCS811Driver) @@ -143,8 +143,8 @@ func WithCCS811MeasMode(mode CCS811DriveMode) func(Config) { } } -//WithCCS811NTCResistance sets reistor value used in the temperature calculations. -//This resistor must be placed between pin 4 and pin 8 of the chip +// WithCCS811NTCResistance sets reistor value used in the temperature calculations. +// This resistor must be placed between pin 4 and pin 8 of the chip func WithCCS811NTCResistance(val uint32) func(Config) { return func(c Config) { d, _ := c.(*CCS811Driver) @@ -152,7 +152,7 @@ func WithCCS811NTCResistance(val uint32) func(Config) { } } -//GetHardwareVersion returns the hardware version of the device in the form of 0x1X +// GetHardwareVersion returns the hardware version of the device in the form of 0x1X func (d *CCS811Driver) GetHardwareVersion() (uint8, error) { d.mutex.Lock() defer d.mutex.Unlock() @@ -165,7 +165,7 @@ func (d *CCS811Driver) GetHardwareVersion() (uint8, error) { return v, nil } -//GetFirmwareBootVersion returns the bootloader version +// GetFirmwareBootVersion returns the bootloader version func (d *CCS811Driver) GetFirmwareBootVersion() (uint16, error) { d.mutex.Lock() defer d.mutex.Unlock() @@ -178,7 +178,7 @@ func (d *CCS811Driver) GetFirmwareBootVersion() (uint16, error) { return v, nil } -//GetFirmwareAppVersion returns the app code version +// GetFirmwareAppVersion returns the app code version func (d *CCS811Driver) GetFirmwareAppVersion() (uint16, error) { d.mutex.Lock() defer d.mutex.Unlock() @@ -191,7 +191,7 @@ func (d *CCS811Driver) GetFirmwareAppVersion() (uint16, error) { return v, nil } -//GetStatus returns the current status of the device +// GetStatus returns the current status of the device func (d *CCS811Driver) GetStatus() (*CCS811Status, error) { d.mutex.Lock() defer d.mutex.Unlock() @@ -205,8 +205,8 @@ func (d *CCS811Driver) GetStatus() (*CCS811Status, error) { return cs, nil } -//GetTemperature returns the device temperature in celcius. -//If you do not have an NTC resistor installed, this function should not be called +// GetTemperature returns the device temperature in celcius. +// If you do not have an NTC resistor installed, this function should not be called func (d *CCS811Driver) GetTemperature() (float32, error) { d.mutex.Lock() defer d.mutex.Unlock() @@ -230,8 +230,8 @@ func (d *CCS811Driver) GetTemperature() (float32, error) { return ntcTemp, nil } -//GetGasData returns the data for the gas sensor. -//eco2 is returned in ppm and tvoc is returned in ppb +// GetGasData returns the data for the gas sensor. +// eco2 is returned in ppm and tvoc is returned in ppb func (d *CCS811Driver) GetGasData() (uint16, uint16, error) { d.mutex.Lock() defer d.mutex.Unlock() @@ -249,7 +249,7 @@ func (d *CCS811Driver) GetGasData() (uint16, uint16, error) { return eco2, tvoC, nil } -//HasData returns true if the device has not errored and temperature/gas data is available +// HasData returns true if the device has not errored and temperature/gas data is available func (d *CCS811Driver) HasData() (bool, error) { s, err := d.GetStatus() if err != nil { @@ -263,7 +263,7 @@ func (d *CCS811Driver) HasData() (bool, error) { return true, nil } -//EnableExternalInterrupt enables the external output hardware interrupt pin 3. +// EnableExternalInterrupt enables the external output hardware interrupt pin 3. func (d *CCS811Driver) EnableExternalInterrupt() error { d.mutex.Lock() defer d.mutex.Unlock() @@ -272,7 +272,7 @@ func (d *CCS811Driver) EnableExternalInterrupt() error { return d.connection.WriteByteData(ccs811RegMeasMode, d.measMode.GetMeasMode()) } -//DisableExternalInterrupt disables the external output hardware interrupt pin 3. +// DisableExternalInterrupt disables the external output hardware interrupt pin 3. func (d *CCS811Driver) DisableExternalInterrupt() error { d.mutex.Lock() defer d.mutex.Unlock() @@ -310,21 +310,21 @@ func (d *CCS811Driver) initialize() error { return nil } -//ResetDevice does a software reset of the device. After this operation is done, -//the user must start the app code before the sensor can take any measurements +// ResetDevice does a software reset of the device. After this operation is done, +// the user must start the app code before the sensor can take any measurements func (d *CCS811Driver) resetDevice() error { return d.connection.WriteBlockData(ccs811RegSwReset, ccs811SwResetSequence) } -//startApp starts the app code in the device. This operation has to be done after a -//software reset to start taking sensor measurements. +// startApp starts the app code in the device. This operation has to be done after a +// software reset to start taking sensor measurements. func (d *CCS811Driver) startApp() error { //Write without data is needed to start the app code _, err := d.connection.Write([]byte{ccs811RegAppStart}) return err } -//updateMeasMode writes the current value of measMode to the measurement mode register. +// updateMeasMode writes the current value of measMode to the measurement mode register. func (d *CCS811Driver) updateMeasMode() error { return d.connection.WriteByteData(ccs811RegMeasMode, d.measMode.GetMeasMode()) } diff --git a/drivers/i2c/ccs811_driver_test.go b/drivers/i2c/ccs811_driver_test.go index b5c23c6b4..56f01cfe6 100644 --- a/drivers/i2c/ccs811_driver_test.go +++ b/drivers/i2c/ccs811_driver_test.go @@ -86,7 +86,7 @@ func TestCCS811GetGasData(t *testing.T) { d, a := initTestCCS811WithStubbedAdaptor() // Create stub function as it is needed by read submethod in driver code a.i2cWriteImpl = func([]byte) (int, error) { return 0, nil } - d.Start() + _ = d.Start() a.i2cReadImpl = tc.readReturn // act eco2, tvoc, err := d.GetGasData() @@ -143,7 +143,7 @@ func TestCCS811GetTemperature(t *testing.T) { d, a := initTestCCS811WithStubbedAdaptor() // Create stub function as it is needed by read submethod in driver code a.i2cWriteImpl = func([]byte) (int, error) { return 0, nil } - d.Start() + _ = d.Start() a.i2cReadImpl = tc.readReturn // act temp, err := d.GetTemperature() @@ -207,7 +207,7 @@ func TestCCS811HasData(t *testing.T) { d, a := initTestCCS811WithStubbedAdaptor() // Create stub function as it is needed by read submethod in driver code a.i2cWriteImpl = func([]byte) (int, error) { return 0, nil } - d.Start() + _ = d.Start() a.i2cReadImpl = tc.readReturn // act result, err := d.HasData() diff --git a/drivers/i2c/drv2605l_driver_test.go b/drivers/i2c/drv2605l_driver_test.go index 1b5b9773c..7fd988847 100644 --- a/drivers/i2c/drv2605l_driver_test.go +++ b/drivers/i2c/drv2605l_driver_test.go @@ -20,7 +20,7 @@ func initTestDRV2605LDriverWithStubbedAdaptor() (*DRV2605LDriver, *i2cTestAdapto // Prime adapter reader to make "Start()" call happy a.i2cReadImpl = func(b []byte) (int, error) { buf := new(bytes.Buffer) - binary.Write(buf, binary.LittleEndian, uint8(42)) + _ = binary.Write(buf, binary.LittleEndian, uint8(42)) copy(b, buf.Bytes()) return buf.Len(), nil } diff --git a/drivers/i2c/grovepi_driver_test.go b/drivers/i2c/grovepi_driver_test.go index 7ccd27da0..dad364537 100644 --- a/drivers/i2c/grovepi_driver_test.go +++ b/drivers/i2c/grovepi_driver_test.go @@ -137,7 +137,7 @@ func TestGrovePiSomeRead(t *testing.T) { for name, tc := range tests { t.Run(name, func(t *testing.T) { g, a := initGrovePiDriverWithStubbedAdaptor() - g.Start() + _ = g.Start() a.written = []byte{} // reset writes of former test and start numCallsRead := 0 a.i2cReadImpl = func(bytes []byte) (i int, e error) { @@ -201,7 +201,7 @@ func TestGrovePiSomeWrite(t *testing.T) { for name, tc := range tests { t.Run(name, func(t *testing.T) { g, a := initGrovePiDriverWithStubbedAdaptor() - g.Start() + _ = g.Start() a.written = []byte{} // reset writes of former test and start a.i2cReadImpl = func(bytes []byte) (i int, e error) { copy(bytes, tc.simResponse) diff --git a/drivers/i2c/helpers_test.go b/drivers/i2c/helpers_test.go index 34c3d83be..b4378cac7 100644 --- a/drivers/i2c/helpers_test.go +++ b/drivers/i2c/helpers_test.go @@ -12,14 +12,6 @@ var rgb = map[string]interface{}{ "blue": 1.0, } -func castColor(color string) byte { - return byte(rgb[color].(float64)) -} - -var red = castColor("red") -var green = castColor("green") -var blue = castColor("blue") - type i2cTestAdaptor struct { name string bus int diff --git a/drivers/i2c/hmc5883l_driver_test.go b/drivers/i2c/hmc5883l_driver_test.go index 955ff5508..a7a88d9b0 100644 --- a/drivers/i2c/hmc5883l_driver_test.go +++ b/drivers/i2c/hmc5883l_driver_test.go @@ -111,7 +111,7 @@ func TestHMC5883LRead(t *testing.T) { for name, tc := range tests { t.Run(name, func(t *testing.T) { d := NewHMC5883LDriver(a, WithHMC5883LGain(int(tc.gain))) - d.Start() + _ = d.Start() // arrange reads returnRead := append(append(tc.inputX, tc.inputZ...), tc.inputY...) a.i2cReadImpl = func(b []byte) (int, error) { @@ -162,7 +162,7 @@ func TestHMC5883L_readRawData(t *testing.T) { }, } d, a := initTestHMC5883LWithStubbedAdaptor() - d.Start() + _ = d.Start() for name, tc := range tests { t.Run(name, func(t *testing.T) { a.written = []byte{} // reset writes of former test and start diff --git a/drivers/i2c/i2c_driver_test.go b/drivers/i2c/i2c_driver_test.go index cb2b15f7d..3fed2a785 100644 --- a/drivers/i2c/i2c_driver_test.go +++ b/drivers/i2c/i2c_driver_test.go @@ -90,7 +90,7 @@ func TestWrite(t *testing.T) { value = 0x25 ) d, a := initDriverWithStubbedAdaptor() - d.Start() + _ = d.Start() // prepare all writes numCallsWrite := 0 a.i2cWriteImpl = func([]byte) (int, error) { @@ -114,7 +114,7 @@ func TestRead(t *testing.T) { want = uint8(0x44) ) d, a := initDriverWithStubbedAdaptor() - d.Start() + _ = d.Start() // prepare all writes numCallsWrite := 0 a.i2cWriteImpl = func(b []byte) (int, error) { diff --git a/drivers/i2c/ina3221_driver.go b/drivers/i2c/ina3221_driver.go index 7c7de2406..1624325fd 100644 --- a/drivers/i2c/ina3221_driver.go +++ b/drivers/i2c/ina3221_driver.go @@ -42,16 +42,17 @@ const ( // INA3221Driver is a driver for the INA3221 three-channel current and bus voltage monitoring device. type INA3221Driver struct { *Driver - halt chan bool } // NewINA3221Driver creates a new driver with the specified i2c interface. // Params: -// c Connector - the Adaptor to use with this Driver +// +// c Connector - the Adaptor to use with this Driver // // Optional params: -// i2c.WithBus(int): bus to use with this driver -// i2c.WithAddress(int): address to use with this driver +// +// i2c.WithBus(int): bus to use with this driver +// i2c.WithAddress(int): address to use with this driver func NewINA3221Driver(c Connector, options ...func(Config)) *INA3221Driver { i := &INA3221Driver{ Driver: NewDriver(c, "INA3221", ina3221DefaultAddress), diff --git a/drivers/i2c/jhd1313m1_driver_test.go b/drivers/i2c/jhd1313m1_driver_test.go index 87acf005e..1c0c99fc9 100644 --- a/drivers/i2c/jhd1313m1_driver_test.go +++ b/drivers/i2c/jhd1313m1_driver_test.go @@ -73,19 +73,19 @@ func TestJHD1313MDriverStartWriteError(t *testing.T) { func TestJHD1313MDriverHalt(t *testing.T) { d := initTestJHD1313M1Driver() - d.Start() + _ = d.Start() gobottest.Assert(t, d.Halt(), nil) } func TestJHD1313MDriverSetRgb(t *testing.T) { d, _ := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() gobottest.Assert(t, d.SetRGB(0x00, 0x00, 0x00), nil) } func TestJHD1313MDriverSetRgbError(t *testing.T) { d, a := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cWriteImpl = func([]byte) (int, error) { return 0, errors.New("write error") @@ -95,13 +95,13 @@ func TestJHD1313MDriverSetRgbError(t *testing.T) { func TestJHD1313MDriverClear(t *testing.T) { d, _ := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() gobottest.Assert(t, d.Clear(), nil) } func TestJHD1313MDriverClearError(t *testing.T) { d, a := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cWriteImpl = func([]byte) (int, error) { return 0, errors.New("write error") @@ -111,19 +111,19 @@ func TestJHD1313MDriverClearError(t *testing.T) { func TestJHD1313MDriverHome(t *testing.T) { d, _ := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() gobottest.Assert(t, d.Home(), nil) } func TestJHD1313MDriverWrite(t *testing.T) { d, _ := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() gobottest.Assert(t, d.Write("Hello"), nil) } func TestJHD1313MDriverWriteError(t *testing.T) { d, a := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cWriteImpl = func([]byte) (int, error) { return 0, errors.New("write error") } @@ -133,13 +133,13 @@ func TestJHD1313MDriverWriteError(t *testing.T) { func TestJHD1313MDriverWriteTwoLines(t *testing.T) { d, _ := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() gobottest.Assert(t, d.Write("Hello\nthere"), nil) } func TestJHD1313MDriverWriteTwoLinesError(t *testing.T) { d, a := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cWriteImpl = func([]byte) (int, error) { return 0, errors.New("write error") @@ -149,52 +149,52 @@ func TestJHD1313MDriverWriteTwoLinesError(t *testing.T) { func TestJHD1313MDriverSetPosition(t *testing.T) { d, _ := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() gobottest.Assert(t, d.SetPosition(2), nil) } func TestJHD1313MDriverSetSecondLinePosition(t *testing.T) { d, _ := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() gobottest.Assert(t, d.SetPosition(18), nil) } func TestJHD1313MDriverSetPositionInvalid(t *testing.T) { d, _ := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() gobottest.Assert(t, d.SetPosition(-1), jhd1313m1ErrInvalidPosition) gobottest.Assert(t, d.SetPosition(32), jhd1313m1ErrInvalidPosition) } func TestJHD1313MDriverScroll(t *testing.T) { d, _ := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() gobottest.Assert(t, d.Scroll(true), nil) } func TestJHD1313MDriverReverseScroll(t *testing.T) { d, _ := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() gobottest.Assert(t, d.Scroll(false), nil) } func TestJHD1313MDriverSetCustomChar(t *testing.T) { d, _ := initTestJHD1313M1DriverWithStubbedAdaptor() data := [8]byte{0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00} - d.Start() + _ = d.Start() gobottest.Assert(t, d.SetCustomChar(0, data), nil) } func TestJHD1313MDriverSetCustomCharError(t *testing.T) { d, _ := initTestJHD1313M1DriverWithStubbedAdaptor() data := [8]byte{0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00} - d.Start() + _ = d.Start() gobottest.Assert(t, d.SetCustomChar(10, data), errors.New("can't set a custom character at a position greater than 7")) } func TestJHD1313MDriverSetCustomCharWriteError(t *testing.T) { d, a := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cWriteImpl = func([]byte) (int, error) { return 0, errors.New("write error") @@ -205,7 +205,7 @@ func TestJHD1313MDriverSetCustomCharWriteError(t *testing.T) { func TestJHD1313MDriverCommands(t *testing.T) { d, _ := initTestJHD1313M1DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() err := d.Command("SetRGB")(map[string]interface{}{"r": "1", "g": "1", "b": "1"}) gobottest.Assert(t, err, nil) diff --git a/drivers/i2c/l3gd20h_driver.go b/drivers/i2c/l3gd20h_driver.go index 14e04f4f8..f88e91b10 100644 --- a/drivers/i2c/l3gd20h_driver.go +++ b/drivers/i2c/l3gd20h_driver.go @@ -57,12 +57,13 @@ type L3GD20HDriver struct { // L3GD20H I2C Triple-Axis Gyroscope. // // Params: -// c Connector - the Adaptor to use with this Driver +// +// c Connector - the Adaptor to use with this Driver // // Optional params: -// i2c.WithBus(int): bus to use with this driver -// i2c.WithAddress(int): address to use with this driver // +// i2c.WithBus(int): bus to use with this driver +// i2c.WithAddress(int): address to use with this driver func NewL3GD20HDriver(c Connector, options ...func(Config)) *L3GD20HDriver { l := &L3GD20HDriver{ Driver: NewDriver(c, "L3GD20H", l3gd20hDefaultAddress, options...), @@ -116,7 +117,7 @@ func (d *L3GD20HDriver) XYZ() (x float32, y float32, z float32, err error) { measurements := make([]byte, 6) reg := l3gd20hReg_OutXLSB | 0x80 // set auto-increment bit - if err = d.connection.ReadBlockData(uint8(reg), measurements); err != nil { + if err := d.connection.ReadBlockData(uint8(reg), measurements); err != nil { return 0, 0, 0, err } @@ -124,16 +125,22 @@ func (d *L3GD20HDriver) XYZ() (x float32, y float32, z float32, err error) { var rawY int16 var rawZ int16 buf := bytes.NewBuffer(measurements) - binary.Read(buf, binary.LittleEndian, &rawX) - binary.Read(buf, binary.LittleEndian, &rawY) - binary.Read(buf, binary.LittleEndian, &rawZ) + if err := binary.Read(buf, binary.LittleEndian, &rawX); err != nil { + return 0, 0, 0, err + } + if err := binary.Read(buf, binary.LittleEndian, &rawY); err != nil { + return 0, 0, 0, err + } + if err := binary.Read(buf, binary.LittleEndian, &rawZ); err != nil { + return 0, 0, 0, err + } sensitivity := l3gdhSensibility[d.scale] return float32(rawX) * sensitivity, float32(rawY) * sensitivity, float32(rawZ) * sensitivity, nil } -func (d *L3GD20HDriver) initialize() (err error) { +func (d *L3GD20HDriver) initialize() error { // reset the gyroscope. if err := d.connection.WriteByteData(l3gd20hReg_Ctl1, 0x00); err != nil { return err diff --git a/drivers/i2c/l3gd20h_driver_test.go b/drivers/i2c/l3gd20h_driver_test.go index e0816f848..892891698 100644 --- a/drivers/i2c/l3gd20h_driver_test.go +++ b/drivers/i2c/l3gd20h_driver_test.go @@ -212,7 +212,7 @@ func TestL3GD20HMeasurementError(t *testing.T) { return 0, errors.New("read error") } - d.Start() + _ = d.Start() _, _, _, err := d.XYZ() gobottest.Assert(t, err, errors.New("read error")) } diff --git a/drivers/i2c/mcp23017_driver_test.go b/drivers/i2c/mcp23017_driver_test.go index 2026e1e4f..a682c0caf 100644 --- a/drivers/i2c/mcp23017_driver_test.go +++ b/drivers/i2c/mcp23017_driver_test.go @@ -35,7 +35,7 @@ func initTestMCP23017WithStubbedAdaptor(b uint8) (*MCP23017Driver, *i2cTestAdapt // create the driver, ready to use for tests a := newI2cTestAdaptor() d := NewMCP23017Driver(a, WithMCP23017Bank(b)) - d.Start() + _ = d.Start() return d, a } diff --git a/drivers/i2c/mpl115a2_driver.go b/drivers/i2c/mpl115a2_driver.go index 40ea3fcce..0791a55ae 100644 --- a/drivers/i2c/mpl115a2_driver.go +++ b/drivers/i2c/mpl115a2_driver.go @@ -89,10 +89,10 @@ func (d *MPL115A2Driver) Temperature() (t float32, err error) { return } -func (d *MPL115A2Driver) initialization() (err error) { +func (d *MPL115A2Driver) initialization() error { data := make([]byte, 8) - if err = d.connection.ReadBlockData(mpl115A2Reg_A0_MSB, data); err != nil { - return + if err := d.connection.ReadBlockData(mpl115A2Reg_A0_MSB, data); err != nil { + return err } var coA0 int16 @@ -101,10 +101,18 @@ func (d *MPL115A2Driver) initialization() (err error) { var coC12 int16 buf := bytes.NewBuffer(data) - binary.Read(buf, binary.BigEndian, &coA0) - binary.Read(buf, binary.BigEndian, &coB1) - binary.Read(buf, binary.BigEndian, &coB2) - binary.Read(buf, binary.BigEndian, &coC12) + if err := binary.Read(buf, binary.BigEndian, &coA0); err != nil { + return err + } + if err := binary.Read(buf, binary.BigEndian, &coB1); err != nil { + return err + } + if err := binary.Read(buf, binary.BigEndian, &coB2); err != nil { + return err + } + if err := binary.Read(buf, binary.BigEndian, &coC12); err != nil { + return err + } coC12 = coC12 >> 2 @@ -113,7 +121,7 @@ func (d *MPL115A2Driver) initialization() (err error) { d.b2 = float32(coB2) / 16384.0 d.c12 = float32(coC12) / 4194304.0 - return + return nil } // getData fetches the latest data from the MPL115A2 @@ -123,7 +131,7 @@ func (d *MPL115A2Driver) getData() (p, t float32, err error) { var pressureComp float32 if err = d.connection.WriteByteData(mpl115A2Reg_StartConversion, 0); err != nil { - return + return 0, 0, err } time.Sleep(5 * time.Millisecond) @@ -133,8 +141,12 @@ func (d *MPL115A2Driver) getData() (p, t float32, err error) { } buf := bytes.NewBuffer(data) - binary.Read(buf, binary.BigEndian, &pressure) - binary.Read(buf, binary.BigEndian, &temperature) + if err := binary.Read(buf, binary.BigEndian, &pressure); err != nil { + return 0, 0, err + } + if err := binary.Read(buf, binary.BigEndian, &temperature); err != nil { + return 0, 0, err + } temperature = temperature >> 6 pressure = pressure >> 6 diff --git a/drivers/i2c/mpl115a2_driver_test.go b/drivers/i2c/mpl115a2_driver_test.go index 19871514c..6891e9e47 100644 --- a/drivers/i2c/mpl115a2_driver_test.go +++ b/drivers/i2c/mpl115a2_driver_test.go @@ -53,7 +53,7 @@ func TestMPL115A2ReadData(t *testing.T) { // // arrange d, a := initTestMPL115A2DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() a.written = []byte{} // arrange coefficients according the example from data sheet d.a0 = 2009.75 @@ -94,7 +94,7 @@ func TestMPL115A2ReadData(t *testing.T) { func TestMPL115A2ReadDataError(t *testing.T) { d, a := initTestMPL115A2DriverWithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cWriteImpl = func([]byte) (int, error) { return 0, errors.New("write error") diff --git a/drivers/i2c/mpu6050_driver.go b/drivers/i2c/mpu6050_driver.go index 0aa1784dc..38b294945 100644 --- a/drivers/i2c/mpu6050_driver.go +++ b/drivers/i2c/mpu6050_driver.go @@ -120,12 +120,13 @@ var mpu6050GyroGain = map[MPU6050GyroFsConfig]float64{ // NewMPU6050Driver creates a new Gobot Driver for an MPU6050 I2C Accelerometer/Gyroscope/Temperature sensor. // // Params: -// conn Connector - the Adaptor to use with this Driver +// +// conn Connector - the Adaptor to use with this Driver // // Optional params: -// i2c.WithBus(int): bus to use with this driver -// i2c.WithAddress(int): address to use with this driver // +// i2c.WithBus(int): bus to use with this driver +// i2c.WithAddress(int): address to use with this driver func NewMPU6050Driver(a Connector, options ...func(Config)) *MPU6050Driver { m := &MPU6050Driver{ Driver: NewDriver(a, "MPU6050", mpu6050DefaultAddress), @@ -219,14 +220,13 @@ func WithMPU6050Gravity(val float64) func(Config) { } // GetData fetches the latest data from the MPU6050 -func (m *MPU6050Driver) GetData() (err error) { +func (m *MPU6050Driver) GetData() error { m.mutex.Lock() defer m.mutex.Unlock() data := make([]byte, 14) - err = m.connection.ReadBlockData(mpu6050Reg_AccelXoutH, data) - if err != nil { - return + if err := m.connection.ReadBlockData(mpu6050Reg_AccelXoutH, data); err != nil { + return err } var accel struct { @@ -242,9 +242,15 @@ func (m *MPU6050Driver) GetData() (err error) { } buf := bytes.NewBuffer(data) - binary.Read(buf, binary.BigEndian, &accel) - binary.Read(buf, binary.BigEndian, &temp) - binary.Read(buf, binary.BigEndian, &gyro) + if err := binary.Read(buf, binary.BigEndian, &accel); err != nil { + return err + } + if err := binary.Read(buf, binary.BigEndian, &temp); err != nil { + return err + } + if err := binary.Read(buf, binary.BigEndian, &gyro); err != nil { + return err + } ag := float64(mpu6050AccelGain[m.accelFs]) / m.gravity m.Accelerometer.X = float64(accel.X) / ag @@ -258,7 +264,7 @@ func (m *MPU6050Driver) GetData() (err error) { m.Gyroscope.Y = float64(gyro.Y) / gg m.Gyroscope.Z = float64(gyro.Z) / gg - return + return nil } func (m *MPU6050Driver) waitForReset() error { @@ -275,43 +281,40 @@ func (m *MPU6050Driver) waitForReset() error { } } -func (m *MPU6050Driver) initialize() (err error) { +func (m *MPU6050Driver) initialize() error { // reset device and wait for reset is finished - if err = m.connection.WriteByteData(mpu6050Reg_PwrMgmt1, mpu6050Pwr1_DeviceResetBit); err != nil { - return + if err := m.connection.WriteByteData(mpu6050Reg_PwrMgmt1, mpu6050Pwr1_DeviceResetBit); err != nil { + return err } - if err = m.waitForReset(); err != nil { - return + if err := m.waitForReset(); err != nil { + return err } // reset signal path register reset := uint8(mpu6050SignalReset_TempBit | mpu6050SignalReset_AccelBit | mpu6050SignalReset_GyroBit) - if err = m.connection.WriteByteData(mpu6050Reg_SignalPathReset, reset); err != nil { - return + if err := m.connection.WriteByteData(mpu6050Reg_SignalPathReset, reset); err != nil { + return err } time.Sleep(100 * time.Millisecond) // configure digital filter bandwidth and external frame synchronization (bits 3...5 are used) generalConf := uint8(m.dlpf) | uint8(m.frameSync)<<3 - if err = m.connection.WriteByteData(mpu6050Reg_GeneralConfig, generalConf); err != nil { - return + if err := m.connection.WriteByteData(mpu6050Reg_GeneralConfig, generalConf); err != nil { + return err } // set full scale range of gyroscope (bits 3 and 4 are used) - if err = m.connection.WriteByteData(mpu6050Reg_GyroConfig, uint8(m.gyroFs)<<3); err != nil { - return + if err := m.connection.WriteByteData(mpu6050Reg_GyroConfig, uint8(m.gyroFs)<<3); err != nil { + return err } // set full scale range of accelerometer (bits 3 and 4 are used) - if err = m.connection.WriteByteData(mpu6050Reg_AccelConfig, uint8(m.accelFs)<<3); err != nil { - return + if err := m.connection.WriteByteData(mpu6050Reg_AccelConfig, uint8(m.accelFs)<<3); err != nil { + return err } // set clock source and reset sleep pwr1 := uint8(m.clock) & ^uint8(mpu6050Pwr1_SleepOnBit) - if err = m.connection.WriteByteData(mpu6050Reg_PwrMgmt1, pwr1); err != nil { - return - } - return + return m.connection.WriteByteData(mpu6050Reg_PwrMgmt1, pwr1) } diff --git a/drivers/i2c/mpu6050_driver_test.go b/drivers/i2c/mpu6050_driver_test.go index 79c052d99..ac9a3ec9a 100644 --- a/drivers/i2c/mpu6050_driver_test.go +++ b/drivers/i2c/mpu6050_driver_test.go @@ -86,7 +86,7 @@ func TestMPU6050GetData(t *testing.T) { // arrange d, adaptor := initTestMPU6050WithStubbedAdaptor() - d.Start() + _ = d.Start() accData := []byte{0x00, 0x01, 0x02, 0x04, 0x08, 0x16} tempData := []byte{0x32, 0x64} @@ -109,7 +109,7 @@ func TestMPU6050GetData(t *testing.T) { return len(b), nil } // act - d.GetData() + _ = d.GetData() // assert gobottest.Assert(t, d.Accelerometer, wantAccel) gobottest.Assert(t, d.Gyroscope, wantGyro) @@ -118,7 +118,7 @@ func TestMPU6050GetData(t *testing.T) { func TestMPU6050GetDataReadError(t *testing.T) { d, adaptor := initTestMPU6050WithStubbedAdaptor() - d.Start() + _ = d.Start() adaptor.i2cReadImpl = func(b []byte) (int, error) { return 0, errors.New("read error") @@ -129,7 +129,7 @@ func TestMPU6050GetDataReadError(t *testing.T) { func TestMPU6050GetDataWriteError(t *testing.T) { d, adaptor := initTestMPU6050WithStubbedAdaptor() - d.Start() + _ = d.Start() adaptor.i2cWriteImpl = func(b []byte) (int, error) { return 0, errors.New("write error") diff --git a/drivers/i2c/pca953x_driver_test.go b/drivers/i2c/pca953x_driver_test.go index 1c0a65dcb..0dfd3aa64 100644 --- a/drivers/i2c/pca953x_driver_test.go +++ b/drivers/i2c/pca953x_driver_test.go @@ -17,7 +17,7 @@ var _ gobot.Driver = (*PCA953xDriver)(nil) func initPCA953xTestDriverWithStubbedAdaptor() (*PCA953xDriver, *i2cTestAdaptor) { a := newI2cTestAdaptor() d := NewPCA953xDriver(a) - d.Start() + _ = d.Start() return d, a } diff --git a/drivers/i2c/pca9685_driver_test.go b/drivers/i2c/pca9685_driver_test.go index 4fcae5a8f..d77484449 100644 --- a/drivers/i2c/pca9685_driver_test.go +++ b/drivers/i2c/pca9685_driver_test.go @@ -137,7 +137,7 @@ func TestPCA9685Commands(t *testing.T) { copy(b, []byte{0x01}) return 1, nil } - d.Start() + _ = d.Start() err := d.Command("PwmWrite")(map[string]interface{}{"pin": "1", "val": "1"}) gobottest.Assert(t, err, nil) diff --git a/drivers/i2c/pcf8583_driver_test.go b/drivers/i2c/pcf8583_driver_test.go index 95439e040..c0a6db1d9 100644 --- a/drivers/i2c/pcf8583_driver_test.go +++ b/drivers/i2c/pcf8583_driver_test.go @@ -16,7 +16,7 @@ var _ gobot.Driver = (*PCF8583Driver)(nil) func initTestPCF8583WithStubbedAdaptor() (*PCF8583Driver, *i2cTestAdaptor) { a := newI2cTestAdaptor() d := NewPCF8583Driver(a) - d.Start() + _ = d.Start() return d, a } diff --git a/drivers/i2c/sht2x_driver.go b/drivers/i2c/sht2x_driver.go index fddaa48ca..3c1e36e1e 100644 --- a/drivers/i2c/sht2x_driver.go +++ b/drivers/i2c/sht2x_driver.go @@ -68,21 +68,20 @@ const ( // SHT2xDriver is a Driver for a SHT2x humidity and temperature sensor type SHT2xDriver struct { *Driver - Units string - sht2xAddress int - accuracy byte - delay time.Duration - crcTable *crc8.Table + Units string + accuracy byte + crcTable *crc8.Table } // NewSHT2xDriver creates a new driver with specified i2c interface // Params: -// c Connector - the Adaptor to use with this Driver +// +// c Connector - the Adaptor to use with this Driver // // Optional params: -// i2c.WithBus(int): bus to use with this driver -// i2c.WithAddress(int): address to use with this driver // +// i2c.WithBus(int): bus to use with this driver +// i2c.WithAddress(int): address to use with this driver func NewSHT2xDriver(c Connector, options ...func(Config)) *SHT2xDriver { // From the document "CRC Checksum Calculation -- For Safe Communication with SHT2x Sensors": crc8Params := crc8.Params{ @@ -206,7 +205,9 @@ func (d *SHT2xDriver) initialize() error { return err } - d.sendAccuracy() + if err := d.sendAccuracy(); err != nil { + return err + } return nil } diff --git a/drivers/i2c/sht2x_driver_test.go b/drivers/i2c/sht2x_driver_test.go index d2d21d174..2578c6757 100644 --- a/drivers/i2c/sht2x_driver_test.go +++ b/drivers/i2c/sht2x_driver_test.go @@ -56,7 +56,7 @@ func TestSHT2xReset(t *testing.T) { a.i2cReadImpl = func(b []byte) (int, error) { return 0, nil } - d.Start() + _ = d.Start() err := d.Reset() gobottest.Assert(t, err, nil) } @@ -74,7 +74,7 @@ func TestSHT2xMeasurements(t *testing.T) { copy(b, buf.Bytes()) return buf.Len(), nil } - d.Start() + _ = d.Start() temp, err := d.Temperature() gobottest.Assert(t, err, nil) gobottest.Assert(t, temp, float32(18.809052)) @@ -97,8 +97,8 @@ func TestSHT2xAccuracy(t *testing.T) { copy(b, buf.Bytes()) return buf.Len(), nil } - d.Start() - d.SetAccuracy(SHT2xAccuracyLow) + _ = d.Start() + _ = d.SetAccuracy(SHT2xAccuracyLow) gobottest.Assert(t, d.Accuracy(), SHT2xAccuracyLow) err := d.sendAccuracy() gobottest.Assert(t, err, nil) @@ -106,7 +106,7 @@ func TestSHT2xAccuracy(t *testing.T) { func TestSHT2xTemperatureCrcError(t *testing.T) { d, a := initTestSHT2xDriverWithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cReadImpl = func(b []byte) (int, error) { buf := new(bytes.Buffer) @@ -123,7 +123,7 @@ func TestSHT2xTemperatureCrcError(t *testing.T) { func TestSHT2xHumidityCrcError(t *testing.T) { d, a := initTestSHT2xDriverWithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cReadImpl = func(b []byte) (int, error) { buf := new(bytes.Buffer) @@ -140,7 +140,7 @@ func TestSHT2xHumidityCrcError(t *testing.T) { func TestSHT2xTemperatureLengthError(t *testing.T) { d, a := initTestSHT2xDriverWithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cReadImpl = func(b []byte) (int, error) { buf := new(bytes.Buffer) @@ -157,7 +157,7 @@ func TestSHT2xTemperatureLengthError(t *testing.T) { func TestSHT2xHumidityLengthError(t *testing.T) { d, a := initTestSHT2xDriverWithStubbedAdaptor() - d.Start() + _ = d.Start() a.i2cReadImpl = func(b []byte) (int, error) { buf := new(bytes.Buffer) diff --git a/drivers/i2c/sht3x_driver.go b/drivers/i2c/sht3x_driver.go index b906a146a..c9d16220a 100644 --- a/drivers/i2c/sht3x_driver.go +++ b/drivers/i2c/sht3x_driver.go @@ -63,19 +63,22 @@ type SHT3xDriver struct { // NewSHT3xDriver creates a new driver with specified i2c interface // Params: -// c Connector - the Adaptor to use with this Driver +// +// c Connector - the Adaptor to use with this Driver // // Optional params: -// i2c.WithBus(int): bus to use with this driver -// i2c.WithAddress(int): address to use with this driver // +// i2c.WithBus(int): bus to use with this driver +// i2c.WithAddress(int): address to use with this driver func NewSHT3xDriver(c Connector, options ...func(Config)) *SHT3xDriver { s := &SHT3xDriver{ Driver: NewDriver(c, "SHT3x", SHT3xAddressA), Units: "C", crcTable: crc8.MakeTable(crc8Params), } - s.SetAccuracy(SHT3xAccuracyHigh) + if err := s.SetAccuracy(SHT3xAccuracyHigh); err != nil { + panic(err) + } for _, option := range options { option(s) diff --git a/drivers/i2c/sht3x_driver_test.go b/drivers/i2c/sht3x_driver_test.go index e9a0a9a16..522b66b9f 100644 --- a/drivers/i2c/sht3x_driver_test.go +++ b/drivers/i2c/sht3x_driver_test.go @@ -189,8 +189,8 @@ func TestSHT3xHeater(t *testing.T) { func TestSHT3xSetHeater(t *testing.T) { d, _ := initTestSHT3xDriverWithStubbedAdaptor() - d.SetHeater(false) - d.SetHeater(true) + _ = d.SetHeater(false) + _ = d.SetHeater(true) } func TestSHT3xSetAccuracy(t *testing.T) { diff --git a/drivers/i2c/ssd1306_driver.go b/drivers/i2c/ssd1306_driver.go index 920b523bb..157d21536 100644 --- a/drivers/i2c/ssd1306_driver.go +++ b/drivers/i2c/ssd1306_driver.go @@ -26,12 +26,12 @@ const ( ssd1306SetComOutput8 = 0xC8 ssd1306SetContrast = 0x81 // scrolling commands - ssd1306ContinuousHScrollRight = 0x26 - ssd1306ContinuousHScrollLeft = 0x27 - ssd1306ContinuousVHScrollRight = 0x29 - ssd1306ContinuousVHScrollLeft = 0x2A - ssd1306StopScroll = 0x2E - ssd1306StartScroll = 0x2F + //ssd1306ContinuousHScrollRight = 0x26 + //ssd1306ContinuousHScrollLeft = 0x27 + //ssd1306ContinuousVHScrollRight = 0x29 + //ssd1306ContinuousVHScrollLeft = 0x2A + //ssd1306StopScroll = 0x2E + //ssd1306StartScroll = 0x2F // adressing settings commands ssd1306SetMemoryAddressingMode = 0x20 ssd1306ColumnAddr = 0x21 @@ -190,15 +190,16 @@ type SSD1306Driver struct { // NewSSD1306Driver creates a new SSD1306Driver. // // Params: -// c Connector - the Adaptor to use with this Driver +// +// c Connector - the Adaptor to use with this Driver // // Optional params: -// WithBus(int): bus to use with this driver -// WithAddress(int): address to use with this driver -// WithSSD1306DisplayWidth(int): width of display (defaults to 128) -// WithSSD1306DisplayHeight(int): height of display (defaults to 64) -// WithSSD1306ExternalVCC: set true when using an external OLED supply (defaults to false) // +// WithBus(int): bus to use with this driver +// WithAddress(int): address to use with this driver +// WithSSD1306DisplayWidth(int): width of display (defaults to 128) +// WithSSD1306DisplayHeight(int): height of display (defaults to 64) +// WithSSD1306ExternalVCC: set true when using an external OLED supply (defaults to false) func NewSSD1306Driver(c Connector, options ...func(Config)) *SSD1306Driver { s := &SSD1306Driver{ Driver: NewDriver(c, "SSD1306", ssd1306DefaultAddress), diff --git a/drivers/i2c/ssd1306_driver_test.go b/drivers/i2c/ssd1306_driver_test.go index b9dfd0109..420446a4b 100644 --- a/drivers/i2c/ssd1306_driver_test.go +++ b/drivers/i2c/ssd1306_driver_test.go @@ -105,13 +105,13 @@ func TestSSD1306Options(t *testing.T) { func TestSSD1306Display(t *testing.T) { s, _ := initTestSSD1306DriverWithStubbedAdaptor(96, 16, false) - s.Start() + _ = s.Start() gobottest.Assert(t, s.Display(), nil) } func TestSSD1306ShowImage(t *testing.T) { s, _ := initTestSSD1306DriverWithStubbedAdaptor(128, 64, false) - s.Start() + _ = s.Start() img := image.NewRGBA(image.Rect(0, 0, 640, 480)) gobottest.Assert(t, s.ShowImage(img), errors.New("image must match display width and height: 128x64")) @@ -121,7 +121,7 @@ func TestSSD1306ShowImage(t *testing.T) { func TestSSD1306Command(t *testing.T) { s, a := initTestSSD1306DriverWithStubbedAdaptor(128, 64, false) - s.Start() + _ = s.Start() a.i2cWriteImpl = func(got []byte) (int, error) { expected := []byte{0x80, 0xFF} @@ -137,7 +137,7 @@ func TestSSD1306Command(t *testing.T) { func TestSSD1306Commands(t *testing.T) { s, a := initTestSSD1306DriverWithStubbedAdaptor(128, 64, false) - s.Start() + _ = s.Start() a.i2cWriteImpl = func(got []byte) (int, error) { expected := []byte{0x80, 0x00, 0x80, 0xFF} @@ -153,7 +153,7 @@ func TestSSD1306Commands(t *testing.T) { func TestSSD1306On(t *testing.T) { s, a := initTestSSD1306DriverWithStubbedAdaptor(128, 64, false) - s.Start() + _ = s.Start() a.i2cWriteImpl = func(got []byte) (int, error) { expected := []byte{0x80, ssd1306SetDisplayOn} @@ -169,7 +169,7 @@ func TestSSD1306On(t *testing.T) { func TestSSD1306Off(t *testing.T) { s, a := initTestSSD1306DriverWithStubbedAdaptor(128, 64, false) - s.Start() + _ = s.Start() a.i2cWriteImpl = func(got []byte) (int, error) { expected := []byte{0x80, ssd1306SetDisplayOff} @@ -185,7 +185,7 @@ func TestSSD1306Off(t *testing.T) { func TestSSD1306Reset(t *testing.T) { s, a := initTestSSD1306DriverWithStubbedAdaptor(128, 64, false) - s.Start() + _ = s.Start() a.i2cWriteImpl = func(got []byte) (int, error) { expectedOff := []byte{0x80, ssd1306SetDisplayOff} diff --git a/drivers/i2c/th02_driver.go b/drivers/i2c/th02_driver.go index 1b1707896..4edee7900 100644 --- a/drivers/i2c/th02_driver.go +++ b/drivers/i2c/th02_driver.go @@ -40,7 +40,7 @@ const ( th02Reg_Config = 0x03 th02Reg_ID = 0x11 - th02Status_ReadyBit = 0x01 // D0 is /RDY + //th02Status_ReadyBit = 0x01 // D0 is /RDY th02Config_StartBit = 0x01 // D0 is START th02Config_HeatBit = 0x02 // D1 is HEAT @@ -48,7 +48,7 @@ const ( th02Config_FastBit = 0x20 // D5 is FAST (if set use 18 ms, but lower accuracy T: 13 bit, H: 11 bit) ) -//Accuracy constants for the TH02 devices (deprecated, use WithFastMode() instead) +// Accuracy constants for the TH02 devices (deprecated, use WithFastMode() instead) const ( TH02HighAccuracy = 0 //High Accuracy (T: 14 bit, H: 12 bit), normal (35 ms) TH02LowAccuracy = 1 //Lower Accuracy (T: 13 bit, H: 11 bit), fast (18 ms) @@ -64,15 +64,17 @@ type TH02Driver struct { // NewTH02Driver creates a new driver with specified i2c interface. // Defaults to: -// - Using high accuracy (lower speed) measurements cycles. -// - Emitting values in "C". If you want F, set Units to "F" +// - Using high accuracy (lower speed) measurements cycles. +// - Emitting values in "C". If you want F, set Units to "F" +// // Params: -// conn Connector - the Adaptor to use with this Driver +// +// conn Connector - the Adaptor to use with this Driver // // Optional params: -// i2c.WithBus(int): bus to use with this driver -// i2c.WithAddress(int): address to use with this driver // +// i2c.WithBus(int): bus to use with this driver +// i2c.WithAddress(int): address to use with this driver func NewTH02Driver(a Connector, options ...func(Config)) *TH02Driver { s := &TH02Driver{ Driver: NewDriver(a, "TH02", th02DefaultAddress, options...), diff --git a/drivers/i2c/tsl2561_driver_test.go b/drivers/i2c/tsl2561_driver_test.go index d5918d22a..276c484fd 100644 --- a/drivers/i2c/tsl2561_driver_test.go +++ b/drivers/i2c/tsl2561_driver_test.go @@ -18,7 +18,7 @@ var _ gobot.Driver = (*TSL2561Driver)(nil) func testIDReader(b []byte) (int, error) { buf := new(bytes.Buffer) // Mock device responding 0xA - binary.Write(buf, binary.LittleEndian, uint8(0x0A)) + _ = binary.Write(buf, binary.LittleEndian, uint8(0x0A)) copy(b, buf.Bytes()) return buf.Len(), nil } @@ -86,9 +86,9 @@ func TestTSL2561DriverRead16(t *testing.T) { a.i2cReadImpl = func(b []byte) (int, error) { buf := new(bytes.Buffer) // send low - binary.Write(buf, binary.LittleEndian, uint8(0xEA)) + _ = binary.Write(buf, binary.LittleEndian, uint8(0xEA)) // send high - binary.Write(buf, binary.LittleEndian, uint8(0xAE)) + _ = binary.Write(buf, binary.LittleEndian, uint8(0xAE)) copy(b, buf.Bytes()) return buf.Len(), nil } @@ -200,7 +200,7 @@ func TestTSL2561DriverGetLuminocityAutoGain(t *testing.T) { return buf.Len(), nil } - d.Start() + _ = d.Start() bb, ir, err := d.GetLuminocity() gobottest.Assert(t, err, nil) gobottest.Assert(t, bb, uint16(12365)) diff --git a/drivers/i2c/wiichuck_driver_test.go b/drivers/i2c/wiichuck_driver_test.go index 0758cbbf6..458d5d607 100644 --- a/drivers/i2c/wiichuck_driver_test.go +++ b/drivers/i2c/wiichuck_driver_test.go @@ -76,7 +76,7 @@ func TestWiichuckDriverCanParse(t *testing.T) { // ------ When value is not encrypted decryptedValue := []byte{1, 2, 3, 4, 5, 6} - d.update(decryptedValue) + _ = d.update(decryptedValue) // - This should be done by WiichuckDriver.parse gobottest.Assert(t, d.data["sx"], float64(45)) @@ -90,7 +90,7 @@ func TestWiichuckDriverCanAdjustOrigins(t *testing.T) { // ------ When value is not encrypted decryptedValue := []byte{1, 2, 3, 4, 5, 6} - d.update(decryptedValue) + _ = d.update(decryptedValue) // - This should be done by WiichuckDriver.adjustOrigins gobottest.Assert(t, d.Joystick()["sx_origin"], float64(45)) @@ -102,17 +102,17 @@ func TestWiichuckDriverCButton(t *testing.T) { // ------ When value is not encrypted decryptedValue := []byte{1, 2, 3, 4, 5, 6} - d.update(decryptedValue) + _ = d.update(decryptedValue) // - This should be done by WiichuckDriver.updateButtons done := make(chan bool) - d.On(d.Event(C), func(data interface{}) { + _ = d.On(d.Event(C), func(data interface{}) { gobottest.Assert(t, data, true) done <- true }) - d.update(decryptedValue) + _ = d.update(decryptedValue) select { case <-done: @@ -126,16 +126,16 @@ func TestWiichuckDriverZButton(t *testing.T) { // ------ When value is not encrypted decryptedValue := []byte{1, 2, 3, 4, 5, 6} - d.update(decryptedValue) + _ = d.update(decryptedValue) done := make(chan bool) - d.On(d.Event(Z), func(data interface{}) { + _ = d.On(d.Event(Z), func(data interface{}) { gobottest.Assert(t, data, true) done <- true }) - d.update(decryptedValue) + _ = d.update(decryptedValue) select { case <-done: @@ -158,12 +158,12 @@ func TestWiichuckDriverUpdateJoystick(t *testing.T) { done := make(chan bool) - d.On(d.Event(Joystick), func(data interface{}) { + _ = d.On(d.Event(Joystick), func(data interface{}) { gobottest.Assert(t, data, expectedData) done <- true }) - d.update(decryptedValue) + _ = d.update(decryptedValue) select { case <-done: @@ -176,7 +176,7 @@ func TestWiichuckDriverEncrypted(t *testing.T) { d := initTestWiichuckDriverWithStubbedAdaptor() encryptedValue := []byte{1, 1, 2, 2, 3, 3} - d.update(encryptedValue) + _ = d.update(encryptedValue) gobottest.Assert(t, d.data["sx"], float64(0)) gobottest.Assert(t, d.data["sy"], float64(0)) diff --git a/drivers/i2c/yl40_driver_test.go b/drivers/i2c/yl40_driver_test.go index 1ee183b13..86ce7714e 100644 --- a/drivers/i2c/yl40_driver_test.go +++ b/drivers/i2c/yl40_driver_test.go @@ -12,7 +12,7 @@ func initTestYL40DriverWithStubbedAdaptor() (*YL40Driver, *i2cTestAdaptor) { adaptor := newI2cTestAdaptor() yl := NewYL40Driver(adaptor, WithPCF8591With400kbitStabilization(0, 2)) WithPCF8591ForceRefresh(1)(yl.PCF8591Driver) - yl.Start() + _ = yl.Start() return yl, adaptor } diff --git a/drivers/spi/ssd1306_driver.go b/drivers/spi/ssd1306_driver.go index 9c8bb94f7..377a0a5be 100644 --- a/drivers/spi/ssd1306_driver.go +++ b/drivers/spi/ssd1306_driver.go @@ -267,11 +267,17 @@ func (s *SSD1306Driver) Set(x, y, c int) { // Reset re-initializes the device to a clean state. func (s *SSD1306Driver) Reset() error { - s.rstDriver.DigitalWrite(1) + if err := s.rstDriver.DigitalWrite(1); err != nil { + return err + } time.Sleep(10 * time.Millisecond) - s.rstDriver.DigitalWrite(0) + if err := s.rstDriver.DigitalWrite(0); err != nil { + return err + } time.Sleep(10 * time.Millisecond) - s.rstDriver.DigitalWrite(1) + if err := s.rstDriver.DigitalWrite(1); err != nil { + return err + } return nil } @@ -291,12 +297,24 @@ func (s *SSD1306Driver) SetContrast(contrast byte) error { // Display sends the memory buffer to the display. func (s *SSD1306Driver) Display() error { - s.command(ssd1306ColumnAddr) - s.command(0) - s.command(uint8(s.DisplayWidth) - 1) - s.command(ssd1306PageAddr) - s.command(0) - s.command(uint8(s.pageSize) - 1) + if err := s.command(ssd1306ColumnAddr); err != nil { + return err + } + if err := s.command(0); err != nil { + return err + } + if err := s.command(uint8(s.DisplayWidth) - 1); err != nil { + return err + } + if err := s.command(ssd1306PageAddr); err != nil { + return err + } + if err := s.command(0); err != nil { + return err + } + if err := s.command(uint8(s.pageSize) - 1); err != nil { + return err + } if err := s.dcDriver.DigitalWrite(1); err != nil { return err } @@ -309,7 +327,9 @@ func (s *SSD1306Driver) ShowImage(img image.Image) error { return fmt.Errorf("Image must match the display width and height") } - s.Clear() + if err := s.Clear(); err != nil { + return err + } for y, w, h := 0, img.Bounds().Dx(), img.Bounds().Dy(); y < h; y++ { for x := 0; x < w; x++ { c := img.At(x, y) @@ -331,64 +351,129 @@ func (s *SSD1306Driver) command(b byte) error { // initialize configures the ssd1306 based on the options passed in when the driver was created func (s *SSD1306Driver) initialize() error { - s.command(ssd1306SetDisplayOff) - s.command(ssd1306SetDisplayClock) + if err := s.command(ssd1306SetDisplayOff); err != nil { + return err + } + if err := s.command(ssd1306SetDisplayClock); err != nil { + return err + } if s.DisplayHeight == 16 { - s.command(0x60) + if err := s.command(0x60); err != nil { + return err + } } else { - s.command(0x80) - } - s.command(ssd1306SetMultiplexRatio) - s.command(uint8(s.DisplayHeight) - 1) - s.command(ssd1306SetDisplayOffset) - s.command(0x0) - s.command(ssd1306SetStartLine) - s.command(0x0) - s.command(ssd1306ChargePumpSetting) + if err := s.command(0x80); err != nil { + return err + } + } + if err := s.command(ssd1306SetMultiplexRatio); err != nil { + return err + } + if err := s.command(uint8(s.DisplayHeight) - 1); err != nil { + return err + } + if err := s.command(ssd1306SetDisplayOffset); err != nil { + return err + } + if err := s.command(0x0); err != nil { + return err + } + if err := s.command(ssd1306SetStartLine); err != nil { + return err + } + if err := s.command(0x0); err != nil { + return err + } + if err := s.command(ssd1306ChargePumpSetting); err != nil { + return err + } if s.ExternalVcc { - s.command(0x10) + if err := s.command(0x10); err != nil { + return err + } } else { - s.command(0x14) - } - s.command(ssd1306SetMemoryAddressingMode) - s.command(0x00) - s.command(ssd1306SetSegmentRemap0) - s.command(0x01) - s.command(ssd1306ComScanInc) - s.command(ssd1306SetComPins) + if err := s.command(0x14); err != nil { + return err + } + } + if err := s.command(ssd1306SetMemoryAddressingMode); err != nil { + return err + } + if err := s.command(0x00); err != nil { + return err + } + if err := s.command(ssd1306SetSegmentRemap0); err != nil { + return err + } + if err := s.command(0x01); err != nil { + return err + } + if err := s.command(ssd1306ComScanInc); err != nil { + return err + } + if err := s.command(ssd1306SetComPins); err != nil { + return err + } if s.DisplayHeight == 64 { - s.command(0x12) + if err := s.command(0x12); err != nil { + return err + } } else { - s.command(0x02) + if err := s.command(0x02); err != nil { + return err + } + } + if err := s.command(ssd1306SetContrast); err != nil { + return err } - s.command(ssd1306SetContrast) if s.DisplayHeight == 64 { if s.ExternalVcc { - s.command(0x9F) + if err := s.command(0x9F); err != nil { + return err + } } else { - s.command(0xCF) + if err := s.command(0xCF); err != nil { + return err + } } } else { - s.command(0x8F) + if err := s.command(0x8F); err != nil { + return err + } + } + if err := s.command(ssd1306SetPrechargePeriod); err != nil { + return err } - s.command(ssd1306SetPrechargePeriod) if s.ExternalVcc { - s.command(0x22) + if err := s.command(0x22); err != nil { + return err + } } else { - s.command(0xF1) - } - s.command(ssd1306SetVComDeselectLevel) - s.command(0x40) - s.command(ssd1306DisplayOnResumeToRAM) - s.command(ssd1306SetDisplayNormal) - s.command(ssd1306DeactivateScroll) - s.command(ssd1306SetDisplayOn) - - return nil + if err := s.command(0xF1); err != nil { + return err + } + } + if err := s.command(ssd1306SetVComDeselectLevel); err != nil { + return err + } + if err := s.command(0x40); err != nil { + return err + } + if err := s.command(ssd1306DisplayOnResumeToRAM); err != nil { + return err + } + if err := s.command(ssd1306SetDisplayNormal); err != nil { + return err + } + if err := s.command(ssd1306DeactivateScroll); err != nil { + return err + } + return s.command(ssd1306SetDisplayOn) } func (s *SSD1306Driver) shutdown() error { - s.Reset() - s.Off() - return nil + if err := s.Reset(); err != nil { + return err + } + return s.Off() } diff --git a/drivers/spi/ssd1306_driver_test.go b/drivers/spi/ssd1306_driver_test.go index d63642443..3e87b9997 100644 --- a/drivers/spi/ssd1306_driver_test.go +++ b/drivers/spi/ssd1306_driver_test.go @@ -25,19 +25,19 @@ func TestDriverSSDStart(t *testing.T) { func TestDriverSSDHalt(t *testing.T) { d := initTestSSDDriver() - d.Start() + _ = d.Start() gobottest.Assert(t, d.Halt(), nil) } func TestDriverSSDDisplay(t *testing.T) { d := initTestSSDDriver() - d.Start() + _ = d.Start() gobottest.Assert(t, d.Display(), nil) } func TestSSD1306DriverShowImage(t *testing.T) { d := initTestSSDDriver() - d.Start() + _ = d.Start() img := image.NewRGBA(image.Rect(0, 0, 640, 480)) gobottest.Assert(t, d.ShowImage(img), errors.New("Image must match the display width and height")) diff --git a/eventer_test.go b/eventer_test.go index 862d58bfc..009dd121c 100644 --- a/eventer_test.go +++ b/eventer_test.go @@ -32,7 +32,7 @@ func TestEventerOn(t *testing.T) { e.AddEvent("test") sem := make(chan bool) - e.On("test", func(data interface{}) { + _ = e.On("test", func(data interface{}) { sem <- true }) @@ -52,7 +52,7 @@ func TestEventerOnce(t *testing.T) { e.AddEvent("test") sem := make(chan bool) - e.Once("test", func(data interface{}) { + _ = e.Once("test", func(data interface{}) { sem <- true }) diff --git a/master.go b/master.go index 10db52f4c..9e16b269d 100644 --- a/master.go +++ b/master.go @@ -4,8 +4,6 @@ import ( "os" "os/signal" "sync/atomic" - - multierror "github.com/hashicorp/go-multierror" ) // JSONMaster is a JSON representation of a Gobot Master. @@ -60,36 +58,32 @@ func NewMaster() *Master { // Start calls the Start method on each robot in its collection of robots. On // error, call Stop to ensure that all robots are returned to a sane, stopped // state. -func (g *Master) Start() (err error) { - if rerr := g.robots.Start(!g.AutoRun); rerr != nil { - err = multierror.Append(err, rerr) - return +func (g *Master) Start() error { + if err := g.robots.Start(!g.AutoRun); err != nil { + return err } g.running.Store(true) - if g.AutoRun { - c := make(chan os.Signal, 1) - g.trap(c) + if !g.AutoRun { + return nil + } - // waiting for interrupt coming on the channel - <-c + c := make(chan os.Signal, 1) + g.trap(c) - // Stop calls the Stop method on each robot in its collection of robots. - g.Stop() - } + // waiting for interrupt coming on the channel + <-c - return err + // Stop calls the Stop method on each robot in its collection of robots. + return g.Stop() } // Stop calls the Stop method on each robot in its collection of robots. -func (g *Master) Stop() (err error) { - if rerr := g.robots.Stop(); rerr != nil { - err = multierror.Append(err, rerr) - } - +func (g *Master) Stop() error { + err := g.robots.Stop() g.running.Store(false) - return + return err } // Running returns if the Master is currently started or not diff --git a/master_test.go b/master_test.go index 3df73ca2f..f6c9159de 100644 --- a/master_test.go +++ b/master_test.go @@ -2,6 +2,7 @@ package gobot import ( "errors" + "fmt" "log" "os" "testing" @@ -76,7 +77,7 @@ func TestMasterStart(t *testing.T) { func TestMasterStartAutoRun(t *testing.T) { g := NewMaster() g.AddRobot(newTestRobot("Robot99")) - go g.Start() + go func() { _ = g.Start() }() time.Sleep(10 * time.Millisecond) gobottest.Assert(t, g.Running(), true) @@ -92,12 +93,12 @@ func TestMasterStartDriverErrors(t *testing.T) { return e } - var expected error - expected = multierror.Append(expected, e) - expected = multierror.Append(expected, e) - expected = multierror.Append(expected, e) + var want error + want = multierror.Append(want, e) + want = multierror.Append(want, e) + want = multierror.Append(want, e) - gobottest.Assert(t, g.Start(), expected) + gobottest.Assert(t, g.Start(), want) gobottest.Assert(t, g.Stop(), nil) testDriverStart = func() (err error) { return } @@ -105,36 +106,38 @@ func TestMasterStartDriverErrors(t *testing.T) { func TestMasterHaltFromRobotDriverErrors(t *testing.T) { g := initTestMaster1Robot() - e := errors.New("driver halt error 1") + var ec int testDriverHalt = func() (err error) { - return e + ec++ + return fmt.Errorf("driver halt error %d", ec) } + defer func() { testDriverHalt = func() error { return nil } }() - var expected error - expected = multierror.Append(expected, e) - expected = multierror.Append(expected, e) - expected = multierror.Append(expected, e) - - gobottest.Assert(t, g.Start(), nil) - gobottest.Assert(t, g.Stop(), expected) + var want error + for i := 1; i <= 3; i++ { + e := fmt.Errorf("driver halt error %d", i) + want = multierror.Append(want, e) + } - testDriverHalt = func() (err error) { return } + gobottest.Assert(t, g.Start(), want) } func TestMasterStartRobotAdaptorErrors(t *testing.T) { g := initTestMaster1Robot() - e := errors.New("adaptor start error 1") - + var ec int testAdaptorConnect = func() (err error) { - return e + ec++ + return fmt.Errorf("adaptor start error %d", ec) } + defer func() { testAdaptorConnect = func() error { return nil } }() - var expected error - expected = multierror.Append(expected, e) - expected = multierror.Append(expected, e) - expected = multierror.Append(expected, e) + var want error + for i := 1; i <= 3; i++ { + e := fmt.Errorf("adaptor start error %d", i) + want = multierror.Append(want, e) + } - gobottest.Assert(t, g.Start(), expected) + gobottest.Assert(t, g.Start(), want) gobottest.Assert(t, g.Stop(), nil) testAdaptorConnect = func() (err error) { return } @@ -142,21 +145,18 @@ func TestMasterStartRobotAdaptorErrors(t *testing.T) { func TestMasterFinalizeErrors(t *testing.T) { g := initTestMaster1Robot() - e := errors.New("adaptor finalize error 2") - + var ec int testAdaptorFinalize = func() (err error) { - return e + ec++ + return fmt.Errorf("adaptor finalize error %d", ec) } + defer func() { testAdaptorFinalize = func() error { return nil } }() - var expected error - expected = multierror.Append(expected, e) - expected = multierror.Append(expected, e) - expected = multierror.Append(expected, e) - - gobottest.Assert(t, g.Start(), nil) - gobottest.Assert(t, g.Stop(), expected) - - testAdaptorFinalize = func() (err error) { - return nil + var want error + for i := 1; i <= 3; i++ { + e := fmt.Errorf("adaptor finalize error %d", i) + want = multierror.Append(want, e) } + + gobottest.Assert(t, g.Start(), want) } diff --git a/platforms/adaptors/digitalpinsadaptor_test.go b/platforms/adaptors/digitalpinsadaptor_test.go index df0f56741..954898ecf 100644 --- a/platforms/adaptors/digitalpinsadaptor_test.go +++ b/platforms/adaptors/digitalpinsadaptor_test.go @@ -268,7 +268,7 @@ func TestDigitalPinConcurrency(t *testing.T) { for retry := 0; retry < 20; retry++ { a := NewDigitalPinsAdaptor(sys, translate) - a.Connect() + _ = a.Connect() var wg sync.WaitGroup for i := 0; i < 20; i++ { @@ -276,7 +276,7 @@ func TestDigitalPinConcurrency(t *testing.T) { pinAsString := strconv.Itoa(i) go func(pin string) { defer wg.Done() - a.DigitalPin(pin) + _, _ = a.DigitalPin(pin) }(pinAsString) } diff --git a/platforms/adaptors/i2cbusadaptor_test.go b/platforms/adaptors/i2cbusadaptor_test.go index b0cab6f8d..b76ee0fd5 100644 --- a/platforms/adaptors/i2cbusadaptor_test.go +++ b/platforms/adaptors/i2cbusadaptor_test.go @@ -80,7 +80,7 @@ func TestI2cFinalize(t *testing.T) { gobottest.Assert(t, a.Finalize(), nil) // arrange gobottest.Assert(t, a.Connect(), nil) - a.GetI2cConnection(0xaf, 1) + _, _ = a.GetI2cConnection(0xaf, 1) gobottest.Assert(t, len(a.buses), 1) // assert that Finalize after GetI2cConnection is working and clean up gobottest.Assert(t, a.Finalize(), nil) @@ -91,7 +91,7 @@ func TestI2cFinalize(t *testing.T) { gobottest.Assert(t, a.Connect(), nil) con, _ := a.GetI2cConnection(0xbf, 1) gobottest.Assert(t, len(a.buses), 1) - con.Write([]byte{0xbf}) + _, _ = con.Write([]byte{0xbf}) fs.WithCloseError = true err := a.Finalize() gobottest.Assert(t, strings.Contains(err.Error(), "close error"), true) diff --git a/platforms/adaptors/pwmpinsadaptor_test.go b/platforms/adaptors/pwmpinsadaptor_test.go index 016301d41..87f8f2f58 100644 --- a/platforms/adaptors/pwmpinsadaptor_test.go +++ b/platforms/adaptors/pwmpinsadaptor_test.go @@ -352,7 +352,7 @@ func TestPWMPinConcurrency(t *testing.T) { for retry := 0; retry < 20; retry++ { a := NewPWMPinsAdaptor(sys, translate) - a.Connect() + _ = a.Connect() var wg sync.WaitGroup for i := 0; i < 20; i++ { @@ -360,7 +360,7 @@ func TestPWMPinConcurrency(t *testing.T) { pinAsString := strconv.Itoa(i) go func(pin string) { defer wg.Done() - a.PWMPin(pin) + _, _ = a.PWMPin(pin) }(pinAsString) } diff --git a/platforms/audio/audio_driver.go b/platforms/audio/audio_driver.go index 025180501..8027a3e54 100644 --- a/platforms/audio/audio_driver.go +++ b/platforms/audio/audio_driver.go @@ -61,10 +61,6 @@ func (d *Driver) Play() []error { return d.Sound(d.Filename()) } -func (d *Driver) adaptor() *Adaptor { - return d.Connection().(*Adaptor) -} - // Start starts the Driver func (d *Driver) Start() (err error) { return diff --git a/platforms/beaglebone/beaglebone_adaptor_test.go b/platforms/beaglebone/beaglebone_adaptor_test.go index 008f896d1..ed5e5a38f 100644 --- a/platforms/beaglebone/beaglebone_adaptor_test.go +++ b/platforms/beaglebone/beaglebone_adaptor_test.go @@ -56,7 +56,7 @@ func TestPWM(t *testing.T) { a, fs := initTestAdaptorWithMockedFilesystem(mockPaths) gobottest.Assert(t, a.PwmWrite("P9_99", 175), errors.New("'P9_99' is not a valid id for a PWM pin")) - a.PwmWrite("P9_21", 175) + _ = a.PwmWrite("P9_21", 175) gobottest.Assert( t, fs.Files["/sys/devices/platform/ocp/48300000.epwmss/48300200.pwm/pwm/pwmchip0/pwm1/period"].Contents, @@ -68,7 +68,7 @@ func TestPWM(t *testing.T) { "343137", ) - a.ServoWrite("P9_21", 100) + _ = a.ServoWrite("P9_21", 100) gobottest.Assert( t, fs.Files["/sys/devices/platform/ocp/48300000.epwmss/48300200.pwm/pwm/pwmchip0/pwm1/period"].Contents, @@ -127,7 +127,7 @@ func TestDigitalIO(t *testing.T) { a, fs := initTestAdaptorWithMockedFilesystem(mockPaths) // DigitalIO - a.DigitalWrite("usr1", 1) + _ = a.DigitalWrite("usr1", 1) gobottest.Assert(t, fs.Files["/sys/class/leds/beaglebone:green:usr1/brightness"].Contents, "1", @@ -137,7 +137,7 @@ func TestDigitalIO(t *testing.T) { err := a.DigitalWrite("usr10101", 1) gobottest.Assert(t, err.Error(), " : /sys/class/leds/beaglebone:green:usr10101/brightness: no such file") - a.DigitalWrite("P9_12", 1) + _ = a.DigitalWrite("P9_12", 1) gobottest.Assert(t, fs.Files["/sys/class/gpio/gpio60/value"].Contents, "1") gobottest.Assert(t, a.DigitalWrite("P9_99", 1), errors.New("'P9_99' is not a valid id for a digital pin")) diff --git a/platforms/ble/ble_client_adaptor.go b/platforms/ble/ble_client_adaptor.go index 7f61414a6..7d815acde 100644 --- a/platforms/ble/ble_client_adaptor.go +++ b/platforms/ble/ble_client_adaptor.go @@ -42,7 +42,6 @@ type ClientAdaptor struct { characteristics map[string]bluetooth.DeviceCharacteristic connected bool - ready chan struct{} withoutResponses bool } @@ -72,10 +71,11 @@ func (b *ClientAdaptor) Address() string { return b.address } func (b *ClientAdaptor) WithoutResponses(use bool) { b.withoutResponses = use } // Connect initiates a connection to the BLE peripheral. Returns true on successful connection. -func (b *ClientAdaptor) Connect() (err error) { +func (b *ClientAdaptor) Connect() error { bleMutex.Lock() defer bleMutex.Unlock() + var err error // enable adaptor b.adpt, err = getBLEAdapter(b.AdapterName) if err != nil { @@ -89,7 +89,9 @@ func (b *ClientAdaptor) Connect() (err error) { ch := make(chan bluetooth.ScanResult, 1) err = b.adpt.Scan(func(adapter *bluetooth.Adapter, result bluetooth.ScanResult) { if result.Address.String() == b.Address() { - b.adpt.StopScan() + if err := b.adpt.StopScan(); err != nil { + panic(err) + } b.SetName(result.LocalName()) ch <- result } @@ -108,6 +110,9 @@ func (b *ClientAdaptor) Connect() (err error) { // get all services/characteristics srvcs, err := b.device.DiscoverServices(nil) + if err != nil { + return err + } for _, srvc := range srvcs { chars, err := srvc.DiscoverCharacteristics(nil) if err != nil { @@ -120,28 +125,30 @@ func (b *ClientAdaptor) Connect() (err error) { } b.connected = true - return + return nil } // Reconnect attempts to reconnect to the BLE peripheral. If it has an active connection // it will first close that connection and then establish a new connection. // Returns true on Successful reconnection -func (b *ClientAdaptor) Reconnect() (err error) { +func (b *ClientAdaptor) Reconnect() error { if b.connected { - b.Disconnect() + if err := b.Disconnect(); err != nil { + return err + } } return b.Connect() } // Disconnect terminates the connection to the BLE peripheral. Returns true on successful disconnect. -func (b *ClientAdaptor) Disconnect() (err error) { - err = b.device.Disconnect() +func (b *ClientAdaptor) Disconnect() error { + err := b.device.Disconnect() time.Sleep(500 * time.Millisecond) - return + return err } // Finalize finalizes the BLEAdaptor -func (b *ClientAdaptor) Finalize() (err error) { +func (b *ClientAdaptor) Finalize() error { return b.Disconnect() } @@ -149,8 +156,7 @@ func (b *ClientAdaptor) Finalize() (err error) { // requested characteristic uuid func (b *ClientAdaptor) ReadCharacteristic(cUUID string) (data []byte, err error) { if !b.connected { - log.Fatalf("Cannot read from BLE device until connected") - return + return nil, fmt.Errorf("Cannot read from BLE device until connected") } cUUID = convertUUID(cUUID) @@ -169,10 +175,9 @@ func (b *ClientAdaptor) ReadCharacteristic(cUUID string) (data []byte, err error // WriteCharacteristic writes bytes to the BLE device for the // requested service and characteristic -func (b *ClientAdaptor) WriteCharacteristic(cUUID string, data []byte) (err error) { +func (b *ClientAdaptor) WriteCharacteristic(cUUID string, data []byte) error { if !b.connected { - log.Println("Cannot write to BLE device until connected") - return + return fmt.Errorf("Cannot write to BLE device until connected") } cUUID = convertUUID(cUUID) @@ -190,10 +195,9 @@ func (b *ClientAdaptor) WriteCharacteristic(cUUID string, data []byte) (err erro // Subscribe subscribes to notifications from the BLE device for the // requested service and characteristic -func (b *ClientAdaptor) Subscribe(cUUID string, f func([]byte, error)) (err error) { +func (b *ClientAdaptor) Subscribe(cUUID string, f func([]byte, error)) error { if !b.connected { - log.Fatalf("Cannot subscribe to BLE device until connected") - return + return fmt.Errorf("Cannot subscribe to BLE device until connected") } cUUID = convertUUID(cUUID) @@ -202,8 +206,7 @@ func (b *ClientAdaptor) Subscribe(cUUID string, f func([]byte, error)) (err erro fn := func(d []byte) { f(d, nil) } - err = char.EnableNotifications(fn) - return + return char.EnableNotifications(fn) } return fmt.Errorf("Unknown characteristic: %s", cUUID) diff --git a/platforms/ble/ble_client_adaptor_test.go b/platforms/ble/ble_client_adaptor_test.go index e3b0e7a53..59bd8e981 100644 --- a/platforms/ble/ble_client_adaptor_test.go +++ b/platforms/ble/ble_client_adaptor_test.go @@ -10,11 +10,6 @@ import ( var _ gobot.Adaptor = (*ClientAdaptor)(nil) -func initTestBLEClientAdaptor() *ClientAdaptor { - a := NewClientAdaptor("D7:99:5A:26:EC:38") - return a -} - func TestBLEClientAdaptor(t *testing.T) { a := NewClientAdaptor("D7:99:5A:26:EC:38") gobottest.Assert(t, a.Address(), "D7:99:5A:26:EC:38") diff --git a/platforms/ble/generic_access_driver.go b/platforms/ble/generic_access_driver.go index 431f20df0..7e4f9d59f 100644 --- a/platforms/ble/generic_access_driver.go +++ b/platforms/ble/generic_access_driver.go @@ -41,12 +41,10 @@ func (b *GenericAccessDriver) adaptor() BLEConnector { } // Start tells driver to get ready to do work -func (b *GenericAccessDriver) Start() (err error) { - return -} +func (b *GenericAccessDriver) Start() error { return nil } // Halt stops driver (void) -func (b *GenericAccessDriver) Halt() (err error) { return } +func (b *GenericAccessDriver) Halt() error { return nil } // GetDeviceName returns the device name for the BLE Peripheral func (b *GenericAccessDriver) GetDeviceName() string { @@ -72,7 +70,9 @@ func (b *GenericAccessDriver) GetAppearance() string { buf := bytes.NewBuffer(c) var val uint16 - binary.Read(buf, binary.LittleEndian, &val) + if err := binary.Read(buf, binary.LittleEndian, &val); err != nil { + panic(err) + } return appearances[val] } diff --git a/platforms/ble/serial_port.go b/platforms/ble/serial_port.go index c783e1dad..db6307591 100644 --- a/platforms/ble/serial_port.go +++ b/platforms/ble/serial_port.go @@ -21,18 +21,19 @@ func NewSerialPort(address string, rid string, tid string) *SerialPort { } // Open opens a connection to a BLE serial device -func (p *SerialPort) Open() (err error) { +func (p *SerialPort) Open() error { p.client = NewClientAdaptor(p.address) - err = p.client.Connect() + if err := p.client.Connect(); err != nil { + return err + } // subscribe to response notifications - p.client.Subscribe(p.rid, func(data []byte, e error) { + return p.client.Subscribe(p.rid, func(data []byte, e error) { p.responseMutex.Lock() p.responseData = append(p.responseData, data...) p.responseMutex.Unlock() }) - return } // Read reads bytes from BLE serial port connection @@ -66,9 +67,8 @@ func (p *SerialPort) Write(b []byte) (n int, err error) { } // Close closes the BLE serial port connection -func (p *SerialPort) Close() (err error) { - p.client.Disconnect() - return +func (p *SerialPort) Close() error { + return p.client.Disconnect() } // Address returns the BLE address diff --git a/platforms/chip/chip_adaptor_test.go b/platforms/chip/chip_adaptor_test.go index e49b9b2cb..612b22164 100644 --- a/platforms/chip/chip_adaptor_test.go +++ b/platforms/chip/chip_adaptor_test.go @@ -92,9 +92,9 @@ func TestFinalizeErrorAfterPWM(t *testing.T) { func TestDigitalIO(t *testing.T) { a, fs := initTestAdaptorWithMockedFilesystem() - a.Connect() + _ = a.Connect() - a.DigitalWrite("CSID7", 1) + _ = a.DigitalWrite("CSID7", 1) gobottest.Assert(t, fs.Files["/sys/class/gpio/gpio139/value"].Contents, "1") fs.Files["/sys/class/gpio/gpio50/value"].Contents = "1" @@ -107,9 +107,9 @@ func TestDigitalIO(t *testing.T) { func TestProDigitalIO(t *testing.T) { a, fs := initTestProAdaptorWithMockedFilesystem() - a.Connect() + _ = a.Connect() - a.DigitalWrite("CSID7", 1) + _ = a.DigitalWrite("CSID7", 1) gobottest.Assert(t, fs.Files["/sys/class/gpio/gpio139/value"].Contents, "1") fs.Files["/sys/class/gpio/gpio50/value"].Contents = "1" @@ -122,7 +122,7 @@ func TestProDigitalIO(t *testing.T) { func TestPWM(t *testing.T) { a, fs := initTestAdaptorWithMockedFilesystem() - a.Connect() + _ = a.Connect() err := a.PwmWrite("PWM0", 100) gobottest.Assert(t, err, nil) diff --git a/platforms/dexter/gopigo3/driver.go b/platforms/dexter/gopigo3/driver.go index 4574372f2..bbed8c56a 100644 --- a/platforms/dexter/gopigo3/driver.go +++ b/platforms/dexter/gopigo3/driver.go @@ -11,6 +11,7 @@ import ( "math" "time" + "github.com/hashicorp/go-multierror" "gobot.io/x/gobot/v2" "gobot.io/x/gobot/v2/drivers/spi" ) @@ -202,25 +203,23 @@ func (g *Driver) SetName(n string) { g.name = n } func (g *Driver) Connection() gobot.Connection { return g.connection.(gobot.Connection) } // Halt stops the driver. -func (g *Driver) Halt() (err error) { - g.resetAll() +func (g *Driver) Halt() error { + err := g.resetAll() time.Sleep(10 * time.Millisecond) - return + return err } // Start initializes the GoPiGo3 -func (g *Driver) Start() (err error) { +func (g *Driver) Start() error { bus := g.GetBusNumberOrDefault(g.connector.SpiDefaultBusNumber()) chip := g.GetChipNumberOrDefault(g.connector.SpiDefaultChipNumber()) mode := g.GetModeOrDefault(g.connector.SpiDefaultMode()) bits := g.GetBitCountOrDefault(g.connector.SpiDefaultBitCount()) maxSpeed := g.GetSpeedOrDefault(g.connector.SpiDefaultMaxSpeed()) + var err error g.connection, err = g.connector.GetSpiConnection(bus, chip, mode, bits, maxSpeed) - if err != nil { - return err - } - return nil + return err } // GetManufacturerName returns the manufacturer from the firmware. @@ -486,7 +485,7 @@ func (g *Driver) SetGroveMode(port Grove, mode GroveMode) error { } // SetPWMDuty sets the pwm duty cycle for the given pin/port. -func (g *Driver) SetPWMDuty(port Grove, duty uint16) (err error) { +func (g *Driver) SetPWMDuty(port Grove, duty uint16) error { if duty > 100 { duty = 100 } @@ -518,26 +517,23 @@ func (g *Driver) SetPWMFreq(port Grove, freq uint16) error { } // PwmWrite implents the pwm interface for the gopigo3. -func (g *Driver) PwmWrite(pin string, val byte) (err error) { +func (g *Driver) PwmWrite(pin string, val byte) error { var ( grovePin, grovePort Grove + err error ) - grovePin, grovePort, _, _, err = getGroveAddresses(pin) - if err != nil { + if grovePin, grovePort, _, _, err = getGroveAddresses(pin); err != nil { return err } - err = g.SetGroveType(grovePort, CUSTOM) - if err != nil { + if err := g.SetGroveType(grovePort, CUSTOM); err != nil { return err } time.Sleep(10 * time.Millisecond) - err = g.SetGroveMode(grovePin, GROVE_OUTPUT_PWM) - if err != nil { + if err = g.SetGroveMode(grovePin, GROVE_OUTPUT_PWM); err != nil { return err } time.Sleep(10 * time.Millisecond) - err = g.SetPWMFreq(grovePin, 24000) - if err != nil { + if err = g.SetPWMFreq(grovePin, 24000); err != nil { return err } val64 := math.Float64frombits(uint64(val)) @@ -555,13 +551,11 @@ func (g *Driver) AnalogRead(pin string) (value int, err error) { if err != nil { return value, err } - err = g.SetGroveType(grovePort, CUSTOM) - if err != nil { + if err := g.SetGroveType(grovePort, CUSTOM); err != nil { return value, err } time.Sleep(10 * time.Millisecond) - err = g.SetGroveMode(grovePin, GROVE_INPUT_ANALOG) - if err != nil { + if err := g.SetGroveMode(grovePin, GROVE_INPUT_ANALOG); err != nil { return value, err } time.Sleep(10 * time.Millisecond) @@ -581,31 +575,29 @@ func (g *Driver) AnalogRead(pin string) (value int, err error) { } // DigitalWrite writes a 0/1 value to the given pin. -func (g *Driver) DigitalWrite(pin string, val byte) (err error) { +func (g *Driver) DigitalWrite(pin string, val byte) error { var ( grovePin, grovePort Grove + err error ) grovePin, grovePort, _, _, err = getGroveAddresses(pin) if err != nil { return err } - err = g.SetGroveType(grovePort, CUSTOM) - if err != nil { + if err := g.SetGroveType(grovePort, CUSTOM); err != nil { return err } time.Sleep(10 * time.Millisecond) - err = g.SetGroveMode(grovePin, GROVE_OUTPUT_DIGITAL) - if err != nil { + if err := g.SetGroveMode(grovePin, GROVE_OUTPUT_DIGITAL); err != nil { return err } time.Sleep(10 * time.Millisecond) - err = g.writeBytes([]byte{ + return g.writeBytes([]byte{ goPiGo3Address, SET_GROVE_STATE, byte(grovePin), byte(val), }) - return err } // DigitalRead reads the 0/1 value from the given pin. @@ -717,17 +709,29 @@ func (g *Driver) readUint32(address, msg byte) (val uint32, err error) { return uint32(r[4])<<24 | uint32(r[5])<<16 | uint32(r[6])<<8 | uint32(r[7]), nil } -func (g *Driver) writeBytes(w []byte) (err error) { +func (g *Driver) writeBytes(w []byte) error { return g.connection.WriteBytes(w) } -func (g *Driver) resetAll() { - g.SetGroveType(AD_1_G+AD_2_G, CUSTOM) +func (g *Driver) resetAll() error { + err := g.SetGroveType(AD_1_G+AD_2_G, CUSTOM) time.Sleep(10 * time.Millisecond) - g.SetGroveMode(AD_1_G+AD_2_G, GROVE_INPUT_DIGITAL) + if e := g.SetGroveMode(AD_1_G+AD_2_G, GROVE_INPUT_DIGITAL); e != nil { + err = multierror.Append(err, e) + } time.Sleep(10 * time.Millisecond) - g.SetMotorPower(MOTOR_LEFT+MOTOR_RIGHT, 0.0) - g.SetMotorLimits(MOTOR_LEFT+MOTOR_RIGHT, 0, 0) - g.SetServo(SERVO_1+SERVO_2, 0) - g.SetLED(LED_EYE_LEFT+LED_EYE_RIGHT+LED_BLINKER_LEFT+LED_BLINKER_RIGHT, 0, 0, 0) + if e := g.SetMotorPower(MOTOR_LEFT+MOTOR_RIGHT, 0.0); e != nil { + err = multierror.Append(err, e) + } + if e := g.SetMotorLimits(MOTOR_LEFT+MOTOR_RIGHT, 0, 0); e != nil { + err = multierror.Append(err, e) + } + if e := g.SetServo(SERVO_1+SERVO_2, 0); e != nil { + err = multierror.Append(err, e) + } + if e := g.SetLED(LED_EYE_LEFT+LED_EYE_RIGHT+LED_BLINKER_LEFT+LED_BLINKER_RIGHT, 0, 0, 0); e != nil { + err = multierror.Append(err, e) + } + + return err } diff --git a/platforms/dexter/gopigo3/driver_test.go b/platforms/dexter/gopigo3/driver_test.go index ee55d7d9e..466376ae4 100644 --- a/platforms/dexter/gopigo3/driver_test.go +++ b/platforms/dexter/gopigo3/driver_test.go @@ -14,7 +14,7 @@ var negativeEncoder = false func initTestDriver() *Driver { d := NewDriver(&TestConnector{}) - d.Start() + _ = d.Start() return d } @@ -273,7 +273,6 @@ func (ctr *TestConnector) SpiDefaultMaxSpeed() int64 { } type TestSpiDevice struct { - bus spi.Connection } func (c TestSpiDevice) Close() error { diff --git a/platforms/digispark/digispark_i2c_test.go b/platforms/digispark/digispark_i2c_test.go index 484931408..d2e1f12cb 100644 --- a/platforms/digispark/digispark_i2c_test.go +++ b/platforms/digispark/digispark_i2c_test.go @@ -16,7 +16,6 @@ var _ i2c.Connector = (*Adaptor)(nil) var i2cData = []byte{5, 4, 3, 2, 1, 0} type i2cMock struct { - address int duration uint direction uint8 dataWritten []byte diff --git a/platforms/dji/tello/driver.go b/platforms/dji/tello/driver.go index 0553ed6eb..b4cb4c647 100644 --- a/platforms/dji/tello/driver.go +++ b/platforms/dji/tello/driver.go @@ -267,11 +267,19 @@ func (d *Driver) Start() error { go func() { defer d.addDoneChReaderCount(-1) - d.On(d.Event(ConnectedEvent), func(interface{}) { - d.SendDateTime() - d.processVideo() + err := d.On(d.Event(ConnectedEvent), func(interface{}) { + if err := d.SendDateTime(); err != nil { + panic(err) + } + if err := d.processVideo(); err != nil { + panic(err) + } }) + if err != nil { + panic(err) + } + cmdLoop: for { select { @@ -287,7 +295,9 @@ func (d *Driver) Start() error { }() // starts notifications coming from drone to video port normally 11111 - d.SendCommand(d.connectionString()) + if err := d.SendCommand(d.connectionString()); err != nil { + return err + } // send stick commands d.addDoneChReaderCount(1) @@ -300,8 +310,7 @@ func (d *Driver) Start() error { case <-d.doneCh: break stickCmdLoop default: - err := d.SendStickCommand() - if err != nil { + if err := d.SendStickCommand(); err != nil { fmt.Println("stick command error:", err) } time.Sleep(20 * time.Millisecond) @@ -313,10 +322,12 @@ func (d *Driver) Start() error { } // Halt stops the driver. -func (d *Driver) Halt() (err error) { +func (d *Driver) Halt() error { // send a landing command when we disconnect, and give it 500ms to be received before we shutdown if d.cmdConn != nil { - d.Land() + if err := d.Land(); err != nil { + return err + } } time.Sleep(500 * time.Millisecond) @@ -332,103 +343,146 @@ func (d *Driver) Halt() (err error) { d.doneCh <- struct{}{} } - return + return nil } // TakeOff tells drones to liftoff and start flying. -func (d *Driver) TakeOff() (err error) { +func (d *Driver) TakeOff() error { buf, _ := d.createPacket(takeoffCommand, 0x68, 0) d.seq++ - binary.Write(buf, binary.LittleEndian, d.seq) - binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())) + if err := binary.Write(buf, binary.LittleEndian, d.seq); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())); err != nil { + return err + } - _, err = d.cmdConn.Write(buf.Bytes()) - return + _, err := d.cmdConn.Write(buf.Bytes()) + return err } // Throw & Go support -func (d *Driver) ThrowTakeOff() (err error) { +func (d *Driver) ThrowTakeOff() error { buf, _ := d.createPacket(throwtakeoffCommand, 0x48, 0) d.seq++ - binary.Write(buf, binary.LittleEndian, d.seq) - binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())) + if err := binary.Write(buf, binary.LittleEndian, d.seq); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())); err != nil { + return err + } - _, err = d.cmdConn.Write(buf.Bytes()) - return + _, err := d.cmdConn.Write(buf.Bytes()) + return err } // Land tells drone to come in for landing. -func (d *Driver) Land() (err error) { +func (d *Driver) Land() error { buf, _ := d.createPacket(landCommand, 0x68, 1) d.seq++ - binary.Write(buf, binary.LittleEndian, d.seq) - binary.Write(buf, binary.LittleEndian, byte(0x00)) - binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())) + if err := binary.Write(buf, binary.LittleEndian, d.seq); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, byte(0x00)); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())); err != nil { + return err + } - _, err = d.cmdConn.Write(buf.Bytes()) - return + _, err := d.cmdConn.Write(buf.Bytes()) + return err } // StopLanding tells drone to stop landing. -func (d *Driver) StopLanding() (err error) { +func (d *Driver) StopLanding() error { buf, _ := d.createPacket(landCommand, 0x68, 1) d.seq++ - binary.Write(buf, binary.LittleEndian, d.seq) - binary.Write(buf, binary.LittleEndian, byte(0x01)) - binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())) + if err := binary.Write(buf, binary.LittleEndian, d.seq); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, byte(0x01)); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())); err != nil { + return err + } - _, err = d.cmdConn.Write(buf.Bytes()) - return + _, err := d.cmdConn.Write(buf.Bytes()) + return err } // PalmLand tells drone to come in for a hand landing. -func (d *Driver) PalmLand() (err error) { +func (d *Driver) PalmLand() error { buf, _ := d.createPacket(palmLandCommand, 0x68, 1) d.seq++ - binary.Write(buf, binary.LittleEndian, d.seq) - binary.Write(buf, binary.LittleEndian, byte(0x00)) - binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())) + if err := binary.Write(buf, binary.LittleEndian, d.seq); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, byte(0x00)); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())); err != nil { + return err + } - _, err = d.cmdConn.Write(buf.Bytes()) - return + _, err := d.cmdConn.Write(buf.Bytes()) + return err } // StartVideo tells Tello to send start info (SPS/PPS) for video stream. -func (d *Driver) StartVideo() (err error) { +func (d *Driver) StartVideo() error { buf, _ := d.createPacket(videoStartCommand, 0x60, 0) - binary.Write(buf, binary.LittleEndian, int16(0x00)) // seq = 0 - binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())) + // seq = 0 + if err := binary.Write(buf, binary.LittleEndian, int16(0x00)); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())); err != nil { + return err + } - _, err = d.cmdConn.Write(buf.Bytes()) - return + _, err := d.cmdConn.Write(buf.Bytes()) + return err } // SetExposure sets the drone camera exposure level. Valid levels are 0, 1, and 2. -func (d *Driver) SetExposure(level int) (err error) { +func (d *Driver) SetExposure(level int) error { if level < 0 || level > 2 { return errors.New("Invalid exposure level") } buf, _ := d.createPacket(exposureCommand, 0x48, 1) d.seq++ - binary.Write(buf, binary.LittleEndian, d.seq) - binary.Write(buf, binary.LittleEndian, byte(level)) - binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())) + if err := binary.Write(buf, binary.LittleEndian, d.seq); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, byte(level)); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())); err != nil { + return err + } - _, err = d.cmdConn.Write(buf.Bytes()) - return + _, err := d.cmdConn.Write(buf.Bytes()) + return err } // SetVideoEncoderRate sets the drone video encoder rate. -func (d *Driver) SetVideoEncoderRate(rate VideoBitRate) (err error) { +func (d *Driver) SetVideoEncoderRate(rate VideoBitRate) error { buf, _ := d.createPacket(videoEncoderRateCommand, 0x68, 1) d.seq++ - binary.Write(buf, binary.LittleEndian, d.seq) - binary.Write(buf, binary.LittleEndian, byte(rate)) - binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())) + if err := binary.Write(buf, binary.LittleEndian, d.seq); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, byte(rate)); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())); err != nil { + return err + } - _, err = d.cmdConn.Write(buf.Bytes()) - return + _, err := d.cmdConn.Write(buf.Bytes()) + return err } // SetFastMode sets the drone throttle to 1. @@ -450,14 +504,18 @@ func (d *Driver) SetSlowMode() error { } // Rate queries the current video bit rate. -func (d *Driver) Rate() (err error) { +func (d *Driver) Rate() error { buf, _ := d.createPacket(videoRateQuery, 0x48, 0) d.seq++ - binary.Write(buf, binary.LittleEndian, d.seq) - binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())) + if err := binary.Write(buf, binary.LittleEndian, d.seq); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())); err != nil { + return err + } - _, err = d.cmdConn.Write(buf.Bytes()) - return + _, err := d.cmdConn.Write(buf.Bytes()) + return err } // bound is a naive implementation that returns the smaller of x or y. @@ -650,89 +708,98 @@ func (d *Driver) CeaseRotation() { } // Bounce tells drone to start/stop performing the bouncing action -func (d *Driver) Bounce() (err error) { +func (d *Driver) Bounce() error { buf, _ := d.createPacket(bounceCommand, 0x68, 1) d.seq++ - binary.Write(buf, binary.LittleEndian, d.seq) + if err := binary.Write(buf, binary.LittleEndian, d.seq); err != nil { + return err + } + if d.bouncing { - binary.Write(buf, binary.LittleEndian, byte(0x31)) + if err := binary.Write(buf, binary.LittleEndian, byte(0x31)); err != nil { + return err + } } else { - binary.Write(buf, binary.LittleEndian, byte(0x30)) + if err := binary.Write(buf, binary.LittleEndian, byte(0x30)); err != nil { + return err + } + } + if err := binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())); err != nil { + return err } - binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())) - _, err = d.cmdConn.Write(buf.Bytes()) + _, err := d.cmdConn.Write(buf.Bytes()) d.bouncing = !d.bouncing - return + return err } // Flip tells drone to flip -func (d *Driver) Flip(direction FlipType) (err error) { +func (d *Driver) Flip(direction FlipType) error { buf, _ := d.createPacket(flipCommand, 0x70, 1) d.seq++ - binary.Write(buf, binary.LittleEndian, d.seq) - binary.Write(buf, binary.LittleEndian, byte(direction)) - binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())) + if err := binary.Write(buf, binary.LittleEndian, d.seq); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, byte(direction)); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())); err != nil { + return err + } - _, err = d.cmdConn.Write(buf.Bytes()) - return + _, err := d.cmdConn.Write(buf.Bytes()) + return err } // FrontFlip tells the drone to perform a front flip. -func (d *Driver) FrontFlip() (err error) { +func (d *Driver) FrontFlip() error { return d.Flip(FlipFront) } // BackFlip tells the drone to perform a back flip. -func (d *Driver) BackFlip() (err error) { +func (d *Driver) BackFlip() error { return d.Flip(FlipBack) } // RightFlip tells the drone to perform a flip to the right. -func (d *Driver) RightFlip() (err error) { +func (d *Driver) RightFlip() error { return d.Flip(FlipRight) } // LeftFlip tells the drone to perform a flip to the left. -func (d *Driver) LeftFlip() (err error) { +func (d *Driver) LeftFlip() error { return d.Flip(FlipLeft) } // ParseFlightData from drone -func (d *Driver) ParseFlightData(b []byte) (fd *FlightData, err error) { +func (d *Driver) ParseFlightData(b []byte) (*FlightData, error) { buf := bytes.NewReader(b) - fd = &FlightData{} + fd := &FlightData{} var data byte if buf.Len() < 24 { - err = errors.New("Invalid buffer length for flight data packet") + err := errors.New("Invalid buffer length for flight data packet") fmt.Println(err) - return + return fd, err } - err = binary.Read(buf, binary.LittleEndian, &fd.Height) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &fd.Height); err != nil { + return fd, err } - err = binary.Read(buf, binary.LittleEndian, &fd.NorthSpeed) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &fd.NorthSpeed); err != nil { + return fd, err } - err = binary.Read(buf, binary.LittleEndian, &fd.EastSpeed) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &fd.EastSpeed); err != nil { + return fd, err } - err = binary.Read(buf, binary.LittleEndian, &fd.VerticalSpeed) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &fd.VerticalSpeed); err != nil { + return fd, err } - err = binary.Read(buf, binary.LittleEndian, &fd.FlyTime) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &fd.FlyTime); err != nil { + return fd, err } - err = binary.Read(buf, binary.LittleEndian, &data) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &data); err != nil { + return fd, err } fd.ImuState = (data >> 0 & 0x1) == 1 fd.PressureState = (data >> 1 & 0x1) == 1 @@ -742,26 +809,21 @@ func (d *Driver) ParseFlightData(b []byte) (fd *FlightData, err error) { fd.GravityState = (data >> 5 & 0x1) == 1 fd.WindState = (data >> 7 & 0x1) == 1 - err = binary.Read(buf, binary.LittleEndian, &fd.ImuCalibrationState) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &fd.ImuCalibrationState); err != nil { + return fd, err } - err = binary.Read(buf, binary.LittleEndian, &fd.BatteryPercentage) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &fd.BatteryPercentage); err != nil { + return fd, err } - err = binary.Read(buf, binary.LittleEndian, &fd.DroneFlyTimeLeft) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &fd.DroneFlyTimeLeft); err != nil { + return fd, err } - err = binary.Read(buf, binary.LittleEndian, &fd.DroneBatteryLeft) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &fd.DroneBatteryLeft); err != nil { + return fd, err } - err = binary.Read(buf, binary.LittleEndian, &data) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &data); err != nil { + return fd, err } fd.Flying = (data >> 0 & 0x1) == 1 fd.OnGround = (data >> 1 & 0x1) == 1 @@ -772,49 +834,46 @@ func (d *Driver) ParseFlightData(b []byte) (fd *FlightData, err error) { fd.BatteryLower = (data >> 6 & 0x1) == 1 fd.FactoryMode = (data >> 7 & 0x1) == 1 - err = binary.Read(buf, binary.LittleEndian, &fd.FlyMode) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &fd.FlyMode); err != nil { + return fd, err } - err = binary.Read(buf, binary.LittleEndian, &fd.ThrowFlyTimer) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &fd.ThrowFlyTimer); err != nil { + return fd, err } - err = binary.Read(buf, binary.LittleEndian, &fd.CameraState) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &fd.CameraState); err != nil { + return fd, err } - err = binary.Read(buf, binary.LittleEndian, &data) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &data); err != nil { + return fd, err } fd.ElectricalMachineryState = int16(data & 0xff) - err = binary.Read(buf, binary.LittleEndian, &data) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &data); err != nil { + return fd, err } fd.FrontIn = (data >> 0 & 0x1) == 1 fd.FrontOut = (data >> 1 & 0x1) == 1 fd.FrontLSC = (data >> 2 & 0x1) == 1 - err = binary.Read(buf, binary.LittleEndian, &data) - if err != nil { - return + if err := binary.Read(buf, binary.LittleEndian, &data); err != nil { + return fd, err } fd.TemperatureHigh = (data >> 0 & 0x1) == 1 - return + return fd, nil } // SendStickCommand sends the joystick command packet to the drone. -func (d *Driver) SendStickCommand() (err error) { +func (d *Driver) SendStickCommand() error { d.cmdMutex.Lock() defer d.cmdMutex.Unlock() buf, _ := d.createPacket(stickCommand, 0x60, 11) - binary.Write(buf, binary.LittleEndian, int16(0x00)) // seq = 0 + // seq = 0 + if err := binary.Write(buf, binary.LittleEndian, int16(0x00)); err != nil { + return err + } // RightX center=1024 left =364 right =-364 axis1 := int16(660.0*d.rx + 1024.0) @@ -832,54 +891,94 @@ func (d *Driver) SendStickCommand() (err error) { axis5 := int16(d.throttle) packedAxis := int64(axis1)&0x7FF | int64(axis2&0x7FF)<<11 | 0x7FF&int64(axis3)<<22 | 0x7FF&int64(axis4)<<33 | int64(axis5)<<44 - binary.Write(buf, binary.LittleEndian, byte(0xFF&packedAxis)) - binary.Write(buf, binary.LittleEndian, byte(packedAxis>>8&0xFF)) - binary.Write(buf, binary.LittleEndian, byte(packedAxis>>16&0xFF)) - binary.Write(buf, binary.LittleEndian, byte(packedAxis>>24&0xFF)) - binary.Write(buf, binary.LittleEndian, byte(packedAxis>>32&0xFF)) - binary.Write(buf, binary.LittleEndian, byte(packedAxis>>40&0xFF)) + if err := binary.Write(buf, binary.LittleEndian, byte(0xFF&packedAxis)); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, byte(packedAxis>>8&0xFF)); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, byte(packedAxis>>16&0xFF)); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, byte(packedAxis>>24&0xFF)); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, byte(packedAxis>>32&0xFF)); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, byte(packedAxis>>40&0xFF)); err != nil { + return err + } now := time.Now() - binary.Write(buf, binary.LittleEndian, byte(now.Hour())) - binary.Write(buf, binary.LittleEndian, byte(now.Minute())) - binary.Write(buf, binary.LittleEndian, byte(now.Second())) - binary.Write(buf, binary.LittleEndian, byte(now.UnixNano()/int64(time.Millisecond)&0xff)) - binary.Write(buf, binary.LittleEndian, byte(now.UnixNano()/int64(time.Millisecond)>>8)) + if err := binary.Write(buf, binary.LittleEndian, byte(now.Hour())); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, byte(now.Minute())); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, byte(now.Second())); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, byte(now.UnixNano()/int64(time.Millisecond)&0xff)); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, byte(now.UnixNano()/int64(time.Millisecond)>>8)); err != nil { + return err + } - binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())) + if err := binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())); err != nil { + return err + } - _, err = d.cmdConn.Write(buf.Bytes()) + _, err := d.cmdConn.Write(buf.Bytes()) - return + return err } // SendDateTime sends the current date/time to the drone. -func (d *Driver) SendDateTime() (err error) { +func (d *Driver) SendDateTime() error { d.cmdMutex.Lock() defer d.cmdMutex.Unlock() buf, _ := d.createPacket(timeCommand, 0x50, 11) d.seq++ - binary.Write(buf, binary.LittleEndian, d.seq) + if err := binary.Write(buf, binary.LittleEndian, d.seq); err != nil { + return err + } now := time.Now() - binary.Write(buf, binary.LittleEndian, byte(0x00)) - binary.Write(buf, binary.LittleEndian, int16(now.Hour())) - binary.Write(buf, binary.LittleEndian, int16(now.Minute())) - binary.Write(buf, binary.LittleEndian, int16(now.Second())) - binary.Write(buf, binary.LittleEndian, int16(now.UnixNano()/int64(time.Millisecond)&0xff)) - binary.Write(buf, binary.LittleEndian, int16(now.UnixNano()/int64(time.Millisecond)>>8)) + if err := binary.Write(buf, binary.LittleEndian, byte(0x00)); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, int16(now.Hour())); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, int16(now.Minute())); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, int16(now.Second())); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, int16(now.UnixNano()/int64(time.Millisecond)&0xff)); err != nil { + return err + } + if err := binary.Write(buf, binary.LittleEndian, int16(now.UnixNano()/int64(time.Millisecond)>>8)); err != nil { + return err + } - binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())) + if err := binary.Write(buf, binary.LittleEndian, CalculateCRC16(buf.Bytes())); err != nil { + return err + } - _, err = d.cmdConn.Write(buf.Bytes()) - return + _, err := d.cmdConn.Write(buf.Bytes()) + return err } // SendCommand is used to send a text command such as the initial connection request to the drone. -func (d *Driver) SendCommand(cmd string) (err error) { - _, err = d.cmdConn.Write([]byte(cmd)) - return +func (d *Driver) SendCommand(cmd string) error { + _, err := d.cmdConn.Write([]byte(cmd)) + return err } func (d *Driver) handleResponse(r io.Reader) error { @@ -897,13 +996,15 @@ func (d *Driver) handleResponse(r io.Reader) error { case wifiMessage: buf := bytes.NewReader(buf[9:10]) wd := &WifiData{} - binary.Read(buf, binary.LittleEndian, &wd.Strength) - binary.Read(buf, binary.LittleEndian, &wd.Disturb) + // TODO: do not drop err, see #948 + _ = binary.Read(buf, binary.LittleEndian, &wd.Strength) + _ = binary.Read(buf, binary.LittleEndian, &wd.Disturb) d.Publish(d.Event(WifiDataEvent), wd) case lightMessage: buf := bytes.NewReader(buf[9:9]) var ld int8 - binary.Read(buf, binary.LittleEndian, &ld) + // TODO: do not drop err, see #948 + _ = binary.Read(buf, binary.LittleEndian, &ld) d.Publish(d.Event(LightStrengthEvent), ld) case logMessage: d.Publish(d.Event(LogEvent), buf[9:]) @@ -975,15 +1076,25 @@ func (d *Driver) processVideo() error { return nil } -func (d *Driver) createPacket(cmd int16, pktType byte, len int16) (buf *bytes.Buffer, err error) { +func (d *Driver) createPacket(cmd int16, pktType byte, len int16) (*bytes.Buffer, error) { l := len + 11 - buf = &bytes.Buffer{} + buf := &bytes.Buffer{} - binary.Write(buf, binary.LittleEndian, byte(messageStart)) - binary.Write(buf, binary.LittleEndian, l<<3) - binary.Write(buf, binary.LittleEndian, CalculateCRC8(buf.Bytes()[0:3])) - binary.Write(buf, binary.LittleEndian, pktType) - binary.Write(buf, binary.LittleEndian, cmd) + if err := binary.Write(buf, binary.LittleEndian, byte(messageStart)); err != nil { + return buf, err + } + if err := binary.Write(buf, binary.LittleEndian, l<<3); err != nil { + return buf, err + } + if err := binary.Write(buf, binary.LittleEndian, CalculateCRC8(buf.Bytes()[0:3])); err != nil { + return buf, err + } + if err := binary.Write(buf, binary.LittleEndian, pktType); err != nil { + return buf, err + } + if err := binary.Write(buf, binary.LittleEndian, cmd); err != nil { + return buf, err + } return buf, nil } diff --git a/platforms/dji/tello/driver_test.go b/platforms/dji/tello/driver_test.go index d7ff5346c..12f270ba8 100644 --- a/platforms/dji/tello/driver_test.go +++ b/platforms/dji/tello/driver_test.go @@ -176,7 +176,7 @@ func TestHaltShouldTerminateAllTheRelatedGoroutines(t *testing.T) { fmt.Println("Done routine 3.") }() - d.Halt() + _ = d.Halt() wg.Wait() gobottest.Assert(t, d.doneChReaderCount, int32(0)) @@ -186,7 +186,7 @@ func TestHaltNotWaitForeverWhenCalledMultipleTimes(t *testing.T) { d := NewDriver("8888") d.cmdConn = &WriteCloserDoNothing{} - d.Halt() - d.Halt() - d.Halt() + _ = d.Halt() + _ = d.Halt() + _ = d.Halt() } diff --git a/platforms/firmata/ble_firmata_adaptor.go b/platforms/firmata/ble_firmata_adaptor.go index fc90ea22d..2aa8d2a6c 100644 --- a/platforms/firmata/ble_firmata_adaptor.go +++ b/platforms/firmata/ble_firmata_adaptor.go @@ -40,7 +40,9 @@ func NewBLEAdaptor(args ...interface{}) *BLEAdaptor { a.SetName(gobot.DefaultName("BLEFirmata")) a.PortOpener = func(port string) (io.ReadWriteCloser, error) { sp := ble.NewSerialPort(address, rid, wid) - sp.Open() + if err := sp.Open(); err != nil { + return sp, err + } return sp, nil } diff --git a/platforms/firmata/client/client.go b/platforms/firmata/client/client.go index 0dea4217e..5b770265d 100644 --- a/platforms/firmata/client/client.go +++ b/platforms/firmata/client/client.go @@ -7,7 +7,6 @@ import ( "fmt" "io" "math" - "sync" "sync/atomic" "time" @@ -71,8 +70,6 @@ type Client struct { connection io.ReadWriteCloser analogPins []int ConnectTimeout time.Duration - initFunc func() error - initMutex sync.Mutex gobot.Eventer } @@ -131,7 +128,7 @@ func (b *Client) setConnected(c bool) { } // Disconnect disconnects the Client -func (b *Client) Disconnect() (err error) { +func (b *Client) Disconnect() error { b.setConnected(false) return b.connection.Close() } @@ -154,51 +151,67 @@ func (b *Client) Pins() []Pin { // Connect connects to the Client given conn. It first resets the firmata board // then continuously polls the firmata board for new information when it's // available. -func (b *Client) Connect(conn io.ReadWriteCloser) (err error) { +func (b *Client) Connect(conn io.ReadWriteCloser) error { if b.Connected() { return ErrConnected } b.connection = conn - b.Reset() + if err := b.Reset(); err != nil { + return err + } connected := make(chan bool, 1) connectError := make(chan error, 1) - b.Once(b.Event("ProtocolVersion"), func(data interface{}) { + if err := b.Once(b.Event("ProtocolVersion"), func(data interface{}) { e := b.FirmwareQuery() if e != nil { b.setConnecting(false) connectError <- e } - }) + }); err != nil { + return err + } - b.Once(b.Event("FirmwareQuery"), func(data interface{}) { + if err := b.Once(b.Event("FirmwareQuery"), func(data interface{}) { e := b.CapabilitiesQuery() if e != nil { b.setConnecting(false) connectError <- e } - }) + }); err != nil { + return err + } - b.Once(b.Event("CapabilityQuery"), func(data interface{}) { + if err := b.Once(b.Event("CapabilityQuery"), func(data interface{}) { e := b.AnalogMappingQuery() if e != nil { b.setConnecting(false) connectError <- e } - }) + }); err != nil { + return err + } - b.Once(b.Event("AnalogMappingQuery"), func(data interface{}) { - b.ReportDigital(0, 1) - b.ReportDigital(1, 1) + if err := b.Once(b.Event("AnalogMappingQuery"), func(data interface{}) { + if err := b.ReportDigital(0, 1); err != nil { + panic(err) + } + if err := b.ReportDigital(1, 1); err != nil { + panic(err) + } b.setConnecting(false) b.setConnected(true) connected <- true - }) + }); err != nil { + return err + } // start it off... b.setConnecting(true) - b.ProtocolVersionQuery() + if err := b.ProtocolVersionQuery(); err != nil { + return err + } go func() { for { @@ -233,7 +246,7 @@ func (b *Client) Connect(conn io.ReadWriteCloser) (err error) { } }() - return + return nil } // Reset sends the SystemReset sysex code. @@ -340,34 +353,33 @@ func (b *Client) I2cConfig(delay int) error { return b.WriteSysex([]byte{I2CConfig, byte(delay & 0xFF), byte((delay >> 8) & 0xFF)}) } -func (b *Client) togglePinReporting(pin int, state int, mode byte) (err error) { +func (b *Client) togglePinReporting(pin int, state int, mode byte) error { if state != 0 { state = 1 } else { state = 0 } - err = b.write([]byte{byte(mode) | byte(pin), byte(state)}) - return + return b.write([]byte{byte(mode) | byte(pin), byte(state)}) } // WriteSysex writes an arbitrary Sysex command to the microcontroller. -func (b *Client) WriteSysex(data []byte) (err error) { +func (b *Client) WriteSysex(data []byte) error { return b.write(append([]byte{StartSysex}, append(data, EndSysex)...)) } -func (b *Client) write(data []byte) (err error) { - _, err = b.connection.Write(data[:]) - return +func (b *Client) write(data []byte) error { + _, err := b.connection.Write(data[:]) + return err } -func (b *Client) read(n int) (buf []byte, err error) { - buf = make([]byte, n) - _, err = io.ReadFull(b.connection, buf) - return +func (b *Client) read(n int) ([]byte, error) { + buf := make([]byte, n) + _, err := io.ReadFull(b.connection, buf) + return buf, err } -func (b *Client) process() (err error) { +func (b *Client) process() error { msgBuf, err := b.read(1) if err != nil { return err @@ -527,5 +539,5 @@ func (b *Client) process() (err error) { b.Publish("SysexResponse", data) } } - return + return nil } diff --git a/platforms/firmata/client/client_test.go b/platforms/firmata/client/client_test.go index fb5b2b32c..b3d557c2a 100644 --- a/platforms/firmata/client/client_test.go +++ b/platforms/firmata/client/client_test.go @@ -95,7 +95,7 @@ func initTestFirmataWithReadWriteCloser(name string, data ...[]byte) (*Client, r for _, d := range data { rwc.addTestReadData(d) - b.process() + _ = b.process() } b.setConnected(true) @@ -128,12 +128,12 @@ func TestProcessProtocolVersion(t *testing.T) { b, rwc := initTestFirmataWithReadWriteCloser(t.Name()) rwc.addTestReadData(testDataProtocolResponse) - b.Once(b.Event("ProtocolVersion"), func(data interface{}) { + _ = b.Once(b.Event("ProtocolVersion"), func(data interface{}) { gobottest.Assert(t, data, "2.3") sem <- true }) - b.process() + _ = b.process() select { case <-sem: @@ -147,12 +147,12 @@ func TestProcessAnalogRead0(t *testing.T) { b, rwc := initTestFirmataWithReadWriteCloser(t.Name(), testDataCapabilitiesResponse, testDataAnalogMappingResponse) rwc.addTestReadData([]byte{0xE0, 0x23, 0x05}) - b.Once(b.Event("AnalogRead0"), func(data interface{}) { + _ = b.Once(b.Event("AnalogRead0"), func(data interface{}) { gobottest.Assert(t, data, 675) sem <- true }) - b.process() + _ = b.process() select { case <-sem: @@ -166,12 +166,12 @@ func TestProcessAnalogRead1(t *testing.T) { b, rwc := initTestFirmataWithReadWriteCloser(t.Name(), testDataCapabilitiesResponse, testDataAnalogMappingResponse) rwc.addTestReadData([]byte{0xE1, 0x23, 0x06}) - b.Once(b.Event("AnalogRead1"), func(data interface{}) { + _ = b.Once(b.Event("AnalogRead1"), func(data interface{}) { gobottest.Assert(t, data, 803) sem <- true }) - b.process() + _ = b.process() select { case <-sem: @@ -186,12 +186,12 @@ func TestProcessDigitalRead2(t *testing.T) { b.pins[2].Mode = Input rwc.addTestReadData([]byte{0x90, 0x04, 0x00}) - b.Once(b.Event("DigitalRead2"), func(data interface{}) { + _ = b.Once(b.Event("DigitalRead2"), func(data interface{}) { gobottest.Assert(t, data, 1) sem <- true }) - b.process() + _ = b.process() select { case <-sem: @@ -206,12 +206,12 @@ func TestProcessDigitalRead4(t *testing.T) { b.pins[4].Mode = Input rwc.addTestReadData([]byte{0x90, 0x16, 0x00}) - b.Once(b.Event("DigitalRead4"), func(data interface{}) { + _ = b.Once(b.Event("DigitalRead4"), func(data interface{}) { gobottest.Assert(t, data, 1) sem <- true }) - b.process() + _ = b.process() select { case <-sem: @@ -246,12 +246,12 @@ func TestProcessPinState13(t *testing.T) { b, rwc := initTestFirmataWithReadWriteCloser(t.Name(), testDataCapabilitiesResponse, testDataAnalogMappingResponse) rwc.addTestReadData([]byte{240, 110, 13, 1, 1, 247}) - b.Once(b.Event("PinState13"), func(data interface{}) { + _ = b.Once(b.Event("PinState13"), func(data interface{}) { gobottest.Assert(t, data, Pin{[]int{0, 1, 4}, 1, 0, 1, 127}) sem <- true }) - b.process() + _ = b.process() select { case <-sem: @@ -285,7 +285,7 @@ func TestProcessI2cReply(t *testing.T) { b, rwc := initTestFirmataWithReadWriteCloser(t.Name()) rwc.addTestReadData([]byte{240, 119, 9, 0, 0, 0, 24, 1, 1, 0, 26, 1, 247}) - b.Once(b.Event("I2cReply"), func(data interface{}) { + _ = b.Once(b.Event("I2cReply"), func(data interface{}) { gobottest.Assert(t, data, I2cReply{ Address: 9, Register: 0, @@ -294,7 +294,7 @@ func TestProcessI2cReply(t *testing.T) { sem <- true }) - b.process() + _ = b.process() select { case <-sem: @@ -308,12 +308,12 @@ func TestProcessFirmwareQuery(t *testing.T) { b, rwc := initTestFirmataWithReadWriteCloser(t.Name()) rwc.addTestReadData(testDataFirmwareResponse) - b.Once(b.Event("FirmwareQuery"), func(data interface{}) { + _ = b.Once(b.Event("FirmwareQuery"), func(data interface{}) { gobottest.Assert(t, data, "StandardFirmata.ino") sem <- true }) - b.process() + _ = b.process() select { case <-sem: @@ -327,12 +327,12 @@ func TestProcessStringData(t *testing.T) { b, rwc := initTestFirmataWithReadWriteCloser(t.Name()) rwc.addTestReadData(append([]byte{240, 0x71}, append([]byte("Hello Firmata!"), 247)...)) - b.Once(b.Event("StringData"), func(data interface{}) { + _ = b.Once(b.Event("StringData"), func(data interface{}) { gobottest.Assert(t, data, "Hello Firmata!") sem <- true }) - b.process() + _ = b.process() select { case <-sem: @@ -347,19 +347,19 @@ func TestConnect(t *testing.T) { rwc.addTestReadData(testDataProtocolResponse) - b.Once(b.Event("ProtocolVersion"), func(data interface{}) { + _ = b.Once(b.Event("ProtocolVersion"), func(data interface{}) { rwc.addTestReadData(testDataFirmwareResponse) }) - b.Once(b.Event("FirmwareQuery"), func(data interface{}) { + _ = b.Once(b.Event("FirmwareQuery"), func(data interface{}) { rwc.addTestReadData(testDataCapabilitiesResponse) }) - b.Once(b.Event("CapabilityQuery"), func(data interface{}) { + _ = b.Once(b.Event("CapabilityQuery"), func(data interface{}) { rwc.addTestReadData(testDataAnalogMappingResponse) }) - b.Once(b.Event("AnalogMappingQuery"), func(data interface{}) { + _ = b.Once(b.Event("AnalogMappingQuery"), func(data interface{}) { rwc.addTestReadData(testDataProtocolResponse) }) @@ -412,12 +412,12 @@ func TestProcessSysexData(t *testing.T) { b, rwc := initTestFirmataWithReadWriteCloser(t.Name()) rwc.addTestReadData([]byte{240, 17, 1, 2, 3, 247}) - b.Once("SysexResponse", func(data interface{}) { + _ = b.Once("SysexResponse", func(data interface{}) { gobottest.Assert(t, data, []byte{240, 17, 1, 2, 3, 247}) sem <- true }) - b.process() + _ = b.process() select { case <-sem: diff --git a/platforms/firmata/firmata_adaptor.go b/platforms/firmata/firmata_adaptor.go index 679c965ba..5686c2bc2 100644 --- a/platforms/firmata/firmata_adaptor.go +++ b/platforms/firmata/firmata_adaptor.go @@ -30,8 +30,8 @@ type firmataBoard interface { } type FirmataAdaptor interface { - Connect() (err error) - Finalize() (err error) + Connect() error + Finalize() error Name() string SetName(n string) WriteSysex(data []byte) error @@ -82,27 +82,25 @@ func NewAdaptor(args ...interface{}) *Adaptor { } // Connect starts a connection to the board. -func (f *Adaptor) Connect() (err error) { +func (f *Adaptor) Connect() error { if f.conn == nil { - sp, e := f.PortOpener(f.Port()) - if e != nil { - return e + sp, err := f.PortOpener(f.Port()) + if err != nil { + return err } f.conn = sp } - if err = f.Board.Connect(f.conn); err != nil { + if err := f.Board.Connect(f.conn); err != nil { return err } - f.Board.On("SysexResponse", func(data interface{}) { + return f.Board.On("SysexResponse", func(data interface{}) { f.Publish("SysexResponse", data) }) - - return } // Disconnect closes the io connection to the Board -func (f *Adaptor) Disconnect() (err error) { +func (f *Adaptor) Disconnect() error { if f.Board != nil { return f.Board.Disconnect() } @@ -110,9 +108,8 @@ func (f *Adaptor) Disconnect() (err error) { } // Finalize terminates the firmata connection -func (f *Adaptor) Finalize() (err error) { - err = f.Disconnect() - return err +func (f *Adaptor) Finalize() error { + return f.Disconnect() } // Port returns the Firmata Adaptors port @@ -135,7 +132,7 @@ func (f *Adaptor) ServoConfig(pin string, min, max int) error { } // ServoWrite writes the 0-180 degree angle to the specified pin. -func (f *Adaptor) ServoWrite(pin string, angle byte) (err error) { +func (f *Adaptor) ServoWrite(pin string, angle byte) error { p, err := strconv.Atoi(pin) if err != nil { return err @@ -147,12 +144,12 @@ func (f *Adaptor) ServoWrite(pin string, angle byte) (err error) { return err } } - err = f.Board.AnalogWrite(p, int(angle)) - return + + return f.Board.AnalogWrite(p, int(angle)) } // PwmWrite writes the 0-254 value to the specified pin -func (f *Adaptor) PwmWrite(pin string, level byte) (err error) { +func (f *Adaptor) PwmWrite(pin string, level byte) error { p, err := strconv.Atoi(pin) if err != nil { return err @@ -164,26 +161,24 @@ func (f *Adaptor) PwmWrite(pin string, level byte) (err error) { return err } } - err = f.Board.AnalogWrite(p, int(level)) - return + + return f.Board.AnalogWrite(p, int(level)) } // DigitalWrite writes a value to the pin. Acceptable values are 1 or 0. -func (f *Adaptor) DigitalWrite(pin string, level byte) (err error) { +func (f *Adaptor) DigitalWrite(pin string, level byte) error { p, err := strconv.Atoi(pin) if err != nil { - return + return err } if f.Board.Pins()[p].Mode != client.Output { - err = f.Board.SetPinMode(p, client.Output) - if err != nil { - return + if err = f.Board.SetPinMode(p, client.Output); err != nil { + return err } } - err = f.Board.DigitalWrite(p, int(level)) - return + return f.Board.DigitalWrite(p, int(level)) } // DigitalRead retrieves digital value from specified pin. @@ -209,21 +204,21 @@ func (f *Adaptor) DigitalRead(pin string) (val int, err error) { // AnalogRead retrieves value from analog pin. // Returns -1 if the response from the board has timed out -func (f *Adaptor) AnalogRead(pin string) (val int, err error) { +func (f *Adaptor) AnalogRead(pin string) (int, error) { p, err := strconv.Atoi(pin) if err != nil { - return + return 0, err } p = f.digitalPin(p) if f.Board.Pins()[p].Mode != client.Analog { - if err = f.Board.SetPinMode(p, client.Analog); err != nil { - return + if err := f.Board.SetPinMode(p, client.Analog); err != nil { + return 0, err } - if err = f.Board.ReportAnalog(p, 1); err != nil { - return + if err := f.Board.ReportAnalog(p, 1); err != nil { + return 0, err } <-time.After(10 * time.Millisecond) } @@ -242,12 +237,14 @@ func (f *Adaptor) digitalPin(pin int) int { // GetI2cConnection returns an i2c connection to a device on a specified bus. // Only supports bus number 0 -func (f *Adaptor) GetI2cConnection(address int, bus int) (connection i2c.Connection, err error) { +func (f *Adaptor) GetI2cConnection(address int, bus int) (i2c.Connection, error) { if bus != 0 { return nil, fmt.Errorf("Invalid bus number %d, only 0 is supported", bus) } - err = f.Board.I2cConfig(0) - return NewFirmataI2cConnection(f, address), err + if err := f.Board.I2cConfig(0); err != nil { + return nil, err + } + return NewFirmataI2cConnection(f, address), nil } // DefaultI2cBus returns the default i2c bus for this platform diff --git a/platforms/firmata/firmata_adaptor_test.go b/platforms/firmata/firmata_adaptor_test.go index 190c11387..e02fc1a10 100644 --- a/platforms/firmata/firmata_adaptor_test.go +++ b/platforms/firmata/firmata_adaptor_test.go @@ -94,7 +94,7 @@ func initTestAdaptor() *Adaptor { a.PortOpener = func(port string) (io.ReadWriteCloser, error) { return &readWriteCloser{}, nil } - a.Connect() + _ = a.Connect() return a } diff --git a/platforms/firmata/firmata_i2c.go b/platforms/firmata/firmata_i2c.go index fc74e48c8..ef7f67d02 100644 --- a/platforms/firmata/firmata_i2c.go +++ b/platforms/firmata/firmata_i2c.go @@ -194,38 +194,40 @@ func (c *firmataI2cConnection) writeAndCheckCount(buf []byte) error { return nil } -func (c *firmataI2cConnection) readInternal(b []byte) (read int, err error) { +func (c *firmataI2cConnection) readInternal(b []byte) (int, error) { ret := make(chan []byte) - if err = c.adaptor.Board.I2cRead(c.address, len(b)); err != nil { - return + if err := c.adaptor.Board.I2cRead(c.address, len(b)); err != nil { + return 0, err } - c.adaptor.Board.Once(c.adaptor.Board.Event("I2cReply"), func(data interface{}) { + if err := c.adaptor.Board.Once(c.adaptor.Board.Event("I2cReply"), func(data interface{}) { ret <- data.(client.I2cReply).Data - }) + }); err != nil { + return 0, err + } result := <-ret copy(b, result) - read = len(result) - - return + return len(result), nil } -func (c *firmataI2cConnection) writeInternal(data []byte) (written int, err error) { +func (c *firmataI2cConnection) writeInternal(data []byte) (int, error) { var chunk []byte + var written int for len(data) >= 16 { chunk, data = data[:16], data[16:] - err = c.adaptor.Board.I2cWrite(c.address, chunk) - if err != nil { - return + if err := c.adaptor.Board.I2cWrite(c.address, chunk); err != nil { + return written, err } written += len(chunk) } if len(data) > 0 { - err = c.adaptor.Board.I2cWrite(c.address, data[:]) + if err := c.adaptor.Board.I2cWrite(c.address, data[:]); err != nil { + return written, err + } written += len(data) } - return + return written, nil } diff --git a/platforms/firmata/firmata_i2c_test.go b/platforms/firmata/firmata_i2c_test.go index 131345c64..92d5169a6 100644 --- a/platforms/firmata/firmata_i2c_test.go +++ b/platforms/firmata/firmata_i2c_test.go @@ -20,7 +20,6 @@ type i2cMockFirmataBoard struct { i2cDataForRead []byte numBytesToRead int i2cWritten []byte - i2cWriteImpl func([]byte) (int, error) } // setup mock for i2c tests diff --git a/platforms/holystone/hs200/hs200_driver.go b/platforms/holystone/hs200/hs200_driver.go index 62fa1e747..c9f2808ef 100644 --- a/platforms/holystone/hs200/hs200_driver.go +++ b/platforms/holystone/hs200/hs200_driver.go @@ -116,7 +116,10 @@ func checksum(c []byte) byte { func (d *Driver) sendUDP() { d.mutex.RLock() defer d.mutex.RUnlock() - d.udpconn.Write(d.cmd) + + if _, err := d.udpconn.Write(d.cmd); err != nil { + panic(err) + } } // Enable enables the drone to start flying. diff --git a/platforms/intel-iot/curie/imu_driver.go b/platforms/intel-iot/curie/imu_driver.go index b9daf6108..ea1e7852f 100644 --- a/platforms/intel-iot/curie/imu_driver.go +++ b/platforms/intel-iot/curie/imu_driver.go @@ -73,18 +73,17 @@ func NewIMUDriver(a *firmata.Adaptor) *IMUDriver { } // Start starts up the IMUDriver -func (imu *IMUDriver) Start() (err error) { - imu.connection.On("SysexResponse", func(res interface{}) { +func (imu *IMUDriver) Start() error { + return imu.connection.On("SysexResponse", func(res interface{}) { data := res.([]byte) - imu.handleEvent(data) + if err := imu.handleEvent(data); err != nil { + panic(err) + } }) - return } // Halt stops the IMUDriver -func (imu *IMUDriver) Halt() (err error) { - return -} +func (imu *IMUDriver) Halt() error { return nil } // Name returns the IMUDriver's name func (imu *IMUDriver) Name() string { return imu.name } @@ -149,47 +148,54 @@ func (imu *IMUDriver) ReadMotion() error { return imu.connection.WriteSysex([]byte{CURIE_IMU, CURIE_IMU_READ_MOTION}) } -func (imu *IMUDriver) handleEvent(data []byte) (err error) { +func (imu *IMUDriver) handleEvent(data []byte) error { if data[1] == CURIE_IMU { switch data[2] { case CURIE_IMU_READ_ACCEL: - val, err := parseAccelerometerData(data) - if err == nil { + if val, err := parseAccelerometerData(data); err == nil { imu.Publish("Accelerometer", val) + } else { + return err } case CURIE_IMU_READ_GYRO: - val, err := parseGyroscopeData(data) - if err == nil { + if val, err := parseGyroscopeData(data); err == nil { imu.Publish("Gyroscope", val) + } else { + return err } case CURIE_IMU_READ_TEMP: - val, err := parseTemperatureData(data) - if err == nil { + if val, err := parseTemperatureData(data); err == nil { imu.Publish("Temperature", val) + } else { + return err } case CURIE_IMU_SHOCK_DETECT: - val, err := parseShockData(data) - if err == nil { + if val, err := parseShockData(data); err == nil { imu.Publish("Shock", val) + } else { + return err } case CURIE_IMU_STEP_COUNTER: - val, err := parseStepData(data) - if err == nil { + if val, err := parseStepData(data); err == nil { imu.Publish("Steps", val) + } else { + return err } case CURIE_IMU_TAP_DETECT: - val, err := parseTapData(data) - if err == nil { + if val, err := parseTapData(data); err == nil { imu.Publish("Tap", val) + } else { + return err } case CURIE_IMU_READ_MOTION: - val, err := parseMotionData(data) - if err == nil { + if val, err := parseMotionData(data); err == nil { imu.Publish("Motion", val) + } else { + return err } } } - return + return nil } func parseAccelerometerData(data []byte) (*AccelerometerData, error) { diff --git a/platforms/intel-iot/curie/imu_driver_test.go b/platforms/intel-iot/curie/imu_driver_test.go index 0d76e1719..845604931 100644 --- a/platforms/intel-iot/curie/imu_driver_test.go +++ b/platforms/intel-iot/curie/imu_driver_test.go @@ -115,7 +115,7 @@ func TestIMUDriverConnection(t *testing.T) { func TestIMUDriverReadAccelerometer(t *testing.T) { d := initTestIMUDriver() - d.Start() + _ = d.Start() gobottest.Assert(t, d.ReadAccelerometer(), nil) } @@ -130,7 +130,7 @@ func TestIMUDriverReadAccelerometerData(t *testing.T) { func TestIMUDriverReadGyroscope(t *testing.T) { d := initTestIMUDriver() - d.Start() + _ = d.Start() gobottest.Assert(t, d.ReadGyroscope(), nil) } @@ -145,7 +145,7 @@ func TestIMUDriverReadGyroscopeData(t *testing.T) { func TestIMUDriverReadTemperature(t *testing.T) { d := initTestIMUDriver() - d.Start() + _ = d.Start() gobottest.Assert(t, d.ReadTemperature(), nil) } @@ -160,7 +160,7 @@ func TestIMUDriverReadTemperatureData(t *testing.T) { func TestIMUDriverEnableShockDetection(t *testing.T) { d := initTestIMUDriver() - d.Start() + _ = d.Start() gobottest.Assert(t, d.EnableShockDetection(true), nil) } @@ -175,7 +175,7 @@ func TestIMUDriverShockDetectData(t *testing.T) { func TestIMUDriverEnableStepCounter(t *testing.T) { d := initTestIMUDriver() - d.Start() + _ = d.Start() gobottest.Assert(t, d.EnableStepCounter(true), nil) } @@ -190,7 +190,7 @@ func TestIMUDriverStepCountData(t *testing.T) { func TestIMUDriverEnableTapDetection(t *testing.T) { d := initTestIMUDriver() - d.Start() + _ = d.Start() gobottest.Assert(t, d.EnableTapDetection(true), nil) } @@ -205,7 +205,7 @@ func TestIMUDriverTapDetectData(t *testing.T) { func TestIMUDriverEnableReadMotion(t *testing.T) { d := initTestIMUDriver() - d.Start() + _ = d.Start() gobottest.Assert(t, d.ReadMotion(), nil) } @@ -220,7 +220,7 @@ func TestIMUDriverReadMotionData(t *testing.T) { func TestIMUDriverHandleEvents(t *testing.T) { d := initTestIMUDriver() - d.Start() + _ = d.Start() gobottest.Assert(t, d.handleEvent([]byte{0xF0, 0x11, 0x00, 0x00, 0x0f, 0x00, 0x0f, 0x00, 0x0f, 0xf7}), nil) gobottest.Assert(t, d.handleEvent([]byte{0xF0, 0x11, 0x01, 0x00, 0x0f, 0x00, 0x0f, 0x00, 0x0f, 0xf7}), nil) diff --git a/platforms/intel-iot/edison/edison_adaptor_test.go b/platforms/intel-iot/edison/edison_adaptor_test.go index 6c373a19a..68baab0d7 100644 --- a/platforms/intel-iot/edison/edison_adaptor_test.go +++ b/platforms/intel-iot/edison/edison_adaptor_test.go @@ -359,17 +359,17 @@ func TestConnectUnknown(t *testing.T) { func TestFinalize(t *testing.T) { a, fs := initTestAdaptorWithMockedFilesystem("arduino") - a.DigitalWrite("3", 1) - a.PwmWrite("5", 100) + _ = a.DigitalWrite("3", 1) + _ = a.PwmWrite("5", 100) - a.GetI2cConnection(0xff, 6) + _, _ = a.GetI2cConnection(0xff, 6) gobottest.Assert(t, a.Finalize(), nil) // assert that finalize after finalize is working gobottest.Assert(t, a.Finalize(), nil) // assert that re-connect is working - a.Connect() + _ = a.Connect() // remove one file to force Finalize error delete(fs.Files, "/sys/class/gpio/unexport") err := a.Finalize() @@ -380,7 +380,7 @@ func TestFinalize(t *testing.T) { func TestFinalizeError(t *testing.T) { a, fs := initTestAdaptorWithMockedFilesystem("arduino") - a.PwmWrite("5", 100) + _ = a.PwmWrite("5", 100) fs.WithWriteError = true err := a.Finalize() @@ -393,10 +393,10 @@ func TestFinalizeError(t *testing.T) { func TestDigitalIO(t *testing.T) { a, fs := initTestAdaptorWithMockedFilesystem("arduino") - a.DigitalWrite("13", 1) + _ = a.DigitalWrite("13", 1) gobottest.Assert(t, fs.Files["/sys/class/gpio/gpio40/value"].Contents, "1") - a.DigitalWrite("2", 0) + _ = a.DigitalWrite("2", 0) i, err := a.DigitalRead("2") gobottest.Assert(t, err, nil) gobottest.Assert(t, i, 0) @@ -407,7 +407,7 @@ func TestDigitalPinInFileError(t *testing.T) { fs := a.sys.UseMockFilesystem(pwmMockPathsMux40) delete(fs.Files, "/sys/class/gpio/gpio40/value") delete(fs.Files, "/sys/class/gpio/gpio40/direction") - a.Connect() + _ = a.Connect() _, err := a.DigitalPin("13") gobottest.Assert(t, strings.Contains(err.Error(), "no such file"), true) @@ -419,7 +419,7 @@ func TestDigitalPinInResistorFileError(t *testing.T) { fs := a.sys.UseMockFilesystem(pwmMockPathsMux40) delete(fs.Files, "/sys/class/gpio/gpio229/value") delete(fs.Files, "/sys/class/gpio/gpio229/direction") - a.Connect() + _ = a.Connect() _, err := a.DigitalPin("13") gobottest.Assert(t, strings.Contains(err.Error(), "no such file"), true) @@ -430,7 +430,7 @@ func TestDigitalPinInLevelShifterFileError(t *testing.T) { fs := a.sys.UseMockFilesystem(pwmMockPathsMux40) delete(fs.Files, "/sys/class/gpio/gpio261/value") delete(fs.Files, "/sys/class/gpio/gpio261/direction") - a.Connect() + _ = a.Connect() _, err := a.DigitalPin("13") gobottest.Assert(t, strings.Contains(err.Error(), "no such file"), true) @@ -441,7 +441,7 @@ func TestDigitalPinInMuxFileError(t *testing.T) { fs := a.sys.UseMockFilesystem(pwmMockPathsMux40) delete(fs.Files, "/sys/class/gpio/gpio243/value") delete(fs.Files, "/sys/class/gpio/gpio243/direction") - a.Connect() + _ = a.Connect() _, err := a.DigitalPin("13") gobottest.Assert(t, strings.Contains(err.Error(), "no such file"), true) @@ -489,7 +489,7 @@ func TestPwmEnableError(t *testing.T) { a := NewAdaptor() fs := a.sys.UseMockFilesystem(pwmMockPathsMux13) delete(fs.Files, "/sys/class/pwm/pwmchip0/pwm1/enable") - a.Connect() + _ = a.Connect() err := a.PwmWrite("5", 100) gobottest.Assert(t, strings.Contains(err.Error(), "/sys/class/pwm/pwmchip0/pwm1/enable: no such file"), true) @@ -609,7 +609,7 @@ func Test_validateI2cBusNumber(t *testing.T) { // arrange a := NewAdaptor(tc.board) a.sys.UseMockFilesystem(pwmMockPathsMux13ArduinoI2c) - a.Connect() + _ = a.Connect() // act err := a.validateAndSetupI2cBusNumber(tc.busNr) // assert diff --git a/platforms/intel-iot/joule/joule_adaptor_test.go b/platforms/intel-iot/joule/joule_adaptor_test.go index b25a8a7bb..43771dc06 100644 --- a/platforms/intel-iot/joule/joule_adaptor_test.go +++ b/platforms/intel-iot/joule/joule_adaptor_test.go @@ -107,8 +107,8 @@ func TestName(t *testing.T) { func TestFinalize(t *testing.T) { a, _ := initTestAdaptorWithMockedFilesystem() - a.DigitalWrite("J12_1", 1) - a.PwmWrite("J12_26", 100) + _ = a.DigitalWrite("J12_1", 1) + _ = a.PwmWrite("J12_26", 100) gobottest.Assert(t, a.Finalize(), nil) @@ -122,10 +122,10 @@ func TestFinalize(t *testing.T) { func TestDigitalIO(t *testing.T) { a, fs := initTestAdaptorWithMockedFilesystem() - a.DigitalWrite("J12_1", 1) + _ = a.DigitalWrite("J12_1", 1) gobottest.Assert(t, fs.Files["/sys/class/gpio/gpio451/value"].Contents, "1") - a.DigitalWrite("J12_1", 0) + _ = a.DigitalWrite("J12_1", 0) i, err := a.DigitalRead("J12_1") gobottest.Assert(t, err, nil) diff --git a/platforms/jetson/jetson_adaptor_test.go b/platforms/jetson/jetson_adaptor_test.go index 994083529..cc44db01a 100644 --- a/platforms/jetson/jetson_adaptor_test.go +++ b/platforms/jetson/jetson_adaptor_test.go @@ -56,9 +56,9 @@ func TestFinalize(t *testing.T) { } a, _ := initTestAdaptorWithMockedFilesystem(mockPaths) - a.DigitalWrite("3", 1) + _ = a.DigitalWrite("3", 1) - a.GetI2cConnection(0xff, 0) + _, _ = a.GetI2cConnection(0xff, 0) gobottest.Assert(t, a.Finalize(), nil) } @@ -136,7 +136,7 @@ func TestDigitalPinConcurrency(t *testing.T) { pinAsString := strconv.Itoa(i) go func(pin string) { defer wg.Done() - a.DigitalPin(pin) + _, _ = a.DigitalPin(pin) }(pinAsString) } diff --git a/platforms/joystick/joystick_adaptor.go b/platforms/joystick/joystick_adaptor.go index b5cdd5beb..2d5f93789 100644 --- a/platforms/joystick/joystick_adaptor.go +++ b/platforms/joystick/joystick_adaptor.go @@ -17,18 +17,20 @@ type joystick interface { type Adaptor struct { name string joystick joystick - connect func(*Adaptor) (err error) + connect func(*Adaptor) error } // NewAdaptor returns a new Joystick Adaptor. func NewAdaptor() *Adaptor { return &Adaptor{ name: gobot.DefaultName("Joystick"), - connect: func(j *Adaptor) (err error) { - sdl.Init(sdl.INIT_JOYSTICK) + connect: func(j *Adaptor) error { + if err := sdl.Init(sdl.INIT_JOYSTICK); err != nil { + return err + } if sdl.NumJoysticks() > 0 { j.joystick = sdl.JoystickOpen(0) - return + return nil } return errors.New("No joystick available") }, @@ -42,13 +44,12 @@ func (j *Adaptor) Name() string { return j.name } func (j *Adaptor) SetName(n string) { j.name = n } // Connect connects to the joystick -func (j *Adaptor) Connect() (err error) { - err = j.connect(j) - return +func (j *Adaptor) Connect() error { + return j.connect(j) } // Finalize closes connection to joystick -func (j *Adaptor) Finalize() (err error) { +func (j *Adaptor) Finalize() error { j.joystick.Close() - return + return nil } diff --git a/platforms/joystick/joystick_adaptor_test.go b/platforms/joystick/joystick_adaptor_test.go index 80bf5a0f3..4f11ca06a 100644 --- a/platforms/joystick/joystick_adaptor_test.go +++ b/platforms/joystick/joystick_adaptor_test.go @@ -37,6 +37,6 @@ func TestAdaptorConnect(t *testing.T) { func TestAdaptorFinalize(t *testing.T) { a := initTestAdaptor() - a.Connect() + _ = a.Connect() gobottest.Assert(t, a.Finalize(), nil) } diff --git a/platforms/joystick/joystick_driver.go b/platforms/joystick/joystick_driver.go index d473bfad3..09634c234 100644 --- a/platforms/joystick/joystick_driver.go +++ b/platforms/joystick/joystick_driver.go @@ -256,7 +256,10 @@ func (j *Driver) loadFile() error { } var jsontype joystickConfig - json.Unmarshal(file, &jsontype) + if err := json.Unmarshal(file, &jsontype); err != nil { + return err + } + j.config = jsontype return nil } diff --git a/platforms/joystick/joystick_driver_test.go b/platforms/joystick/joystick_driver_test.go index fa4ea047e..8084e8365 100644 --- a/platforms/joystick/joystick_driver_test.go +++ b/platforms/joystick/joystick_driver_test.go @@ -18,7 +18,7 @@ func initTestDriver(config string) *Driver { j.joystick = &testJoystick{} return nil } - a.Connect() + _ = a.Connect() d := NewDriver(a, config) d.poll = func() sdl.Event { return nil @@ -51,14 +51,14 @@ func TestDriverHalt(t *testing.T) { func TestDriverHandleEvent(t *testing.T) { sem := make(chan bool) d := initTestDriver("./configs/xbox360_power_a_mini_proex.json") - d.Start() + _ = d.Start() // left x stick - d.On(d.Event("left_x"), func(data interface{}) { + _ = d.On(d.Event("left_x"), func(data interface{}) { gobottest.Assert(t, int16(100), data.(int16)) sem <- true }) - d.handleEvent(&sdl.JoyAxisEvent{ + _ = d.handleEvent(&sdl.JoyAxisEvent{ Which: 0, Axis: 0, Value: 100, @@ -70,10 +70,10 @@ func TestDriverHandleEvent(t *testing.T) { } // x button press - d.On(d.Event("x_press"), func(data interface{}) { + _ = d.On(d.Event("x_press"), func(data interface{}) { sem <- true }) - d.handleEvent(&sdl.JoyButtonEvent{ + _ = d.handleEvent(&sdl.JoyButtonEvent{ Which: 0, Button: 2, State: 1, @@ -85,10 +85,10 @@ func TestDriverHandleEvent(t *testing.T) { } // x button release - d.On(d.Event("x_release"), func(data interface{}) { + _ = d.On(d.Event("x_release"), func(data interface{}) { sem <- true }) - d.handleEvent(&sdl.JoyButtonEvent{ + _ = d.handleEvent(&sdl.JoyButtonEvent{ Which: 0, Button: 2, State: 0, @@ -100,10 +100,10 @@ func TestDriverHandleEvent(t *testing.T) { } // down button press - d.On(d.Event("down_press"), func(data interface{}) { + _ = d.On(d.Event("down_press"), func(data interface{}) { sem <- true }) - d.handleEvent(&sdl.JoyHatEvent{ + _ = d.handleEvent(&sdl.JoyHatEvent{ Which: 0, Hat: 0, Value: 4, diff --git a/platforms/keyboard/keyboard_driver.go b/platforms/keyboard/keyboard_driver.go index fbfe856db..1e8dd0aec 100644 --- a/platforms/keyboard/keyboard_driver.go +++ b/platforms/keyboard/keyboard_driver.go @@ -15,7 +15,7 @@ const ( // Driver is gobot software device to the keyboard type Driver struct { name string - connect func(*Driver) (err error) + connect func(*Driver) error listen func(*Driver) stdin *os.File gobot.Eventer @@ -25,20 +25,22 @@ type Driver struct { func NewDriver() *Driver { k := &Driver{ name: gobot.DefaultName("Keyboard"), - connect: func(k *Driver) (err error) { + connect: func(k *Driver) error { if err := configure(); err != nil { return err } k.stdin = os.Stdin - return + return nil }, listen: func(k *Driver) { ctrlc := bytes{3} for { var keybuf bytes - k.stdin.Read(keybuf[0:3]) + if _, err := k.stdin.Read(keybuf[0:3]); err != nil { + panic(err) + } if keybuf == ctrlc { proc, err := os.FindProcess(os.Getpid()) @@ -46,7 +48,9 @@ func NewDriver() *Driver { log.Fatal(err) } - proc.Signal(os.Interrupt) + if err := proc.Signal(os.Interrupt); err != nil { + panic(err) + } break } @@ -73,20 +77,20 @@ func (k *Driver) Connection() gobot.Connection { return nil } // Start initializes keyboard by grabbing key events as they come in and // publishing each as a key event -func (k *Driver) Start() (err error) { - if err = k.connect(k); err != nil { +func (k *Driver) Start() error { + if err := k.connect(k); err != nil { return err } go k.listen(k) - return + return nil } // Halt stops keyboard driver -func (k *Driver) Halt() (err error) { +func (k *Driver) Halt() error { if originalState != "" { return restore() } - return + return nil } diff --git a/platforms/leap/leap_motion_driver.go b/platforms/leap/leap_motion_driver.go index a31025db1..f420d475f 100644 --- a/platforms/leap/leap_motion_driver.go +++ b/platforms/leap/leap_motion_driver.go @@ -3,6 +3,7 @@ package leap import ( "encoding/json" "io" + "log" "gobot.io/x/gobot/v2" "golang.org/x/net/websocket" @@ -38,7 +39,9 @@ func NewDriver(a *Adaptor) *Driver { connection: a, Eventer: gobot.NewEventer(), receive: func(ws io.ReadWriteCloser, msg *[]byte) { - websocket.Message.Receive(ws.(*websocket.Conn), msg) + if err := websocket.Message.Receive(ws.(*websocket.Conn), msg); err != nil { + panic(err) + } }, } @@ -62,15 +65,14 @@ func (l *Driver) adaptor() *Adaptor { return l.Connection().(*Adaptor) } -func enableFeature(l *Driver, feature string) (err error) { +func enableFeature(l *Driver, feature string) error { command := map[string]bool{feature: true} - b, e := json.Marshal(command) - if e != nil { - return e + b, err := json.Marshal(command) + if err != nil { + return err } - _, e = l.adaptor().ws.Write(b) - if e != nil { - return e + if _, err = l.adaptor().ws.Write(b); err != nil { + return err } return nil @@ -84,22 +86,26 @@ func enableFeature(l *Driver, feature string) (err error) { // "message" - Emits Frame on new message received from Leap. // "hand" - Emits Hand when detected in message from Leap. // "gesture" - Emits Gesture when detected in message from Leap. -func (l *Driver) Start() (err error) { - err = enableFeature(l, "enableGestures") - if err != nil { +func (l *Driver) Start() error { + if err := enableFeature(l, "enableGestures"); err != nil { return err } - err = enableFeature(l, "background") - if err != nil { + if err := enableFeature(l, "background"); err != nil { return err } go func() { var msg []byte var frame Frame + var err error for { l.receive(l.adaptor().ws, &msg) - frame = l.ParseFrame(msg) + frame, err = l.ParseFrame(msg) + if err != nil { + log.Println(err) + continue + } + l.Publish(MessageEvent, frame) for _, hand := range frame.Hands { @@ -112,8 +118,8 @@ func (l *Driver) Start() (err error) { } }() - return + return nil } // Halt returns nil if driver is halted successfully -func (l *Driver) Halt() (errs error) { return } +func (l *Driver) Halt() error { return nil } diff --git a/platforms/leap/leap_motion_driver_test.go b/platforms/leap/leap_motion_driver_test.go index 90267ac99..73dc0cd8c 100644 --- a/platforms/leap/leap_motion_driver_test.go +++ b/platforms/leap/leap_motion_driver_test.go @@ -43,7 +43,7 @@ func initTestLeapMotionDriver() (*Driver, *NullReadWriteCloser) { a.connect = func(port string) (io.ReadWriteCloser, error) { return rwc, nil } - a.Connect() + _ = a.Connect() d := NewDriver(a) d.receive = func(ws io.ReadWriteCloser, buf *[]byte) { @@ -83,7 +83,7 @@ func TestLeapMotionDriverHalt(t *testing.T) { func TestLeapMotionDriverParser(t *testing.T) { d, _ := initTestLeapMotionDriver() file, _ := os.ReadFile("./test/support/example_frame.json") - parsedFrame := d.ParseFrame(file) + parsedFrame, _ := d.ParseFrame(file) if parsedFrame.Hands == nil || parsedFrame.Pointables == nil || parsedFrame.Gestures == nil { t.Errorf("ParseFrame incorrectly parsed frame") diff --git a/platforms/leap/parser.go b/platforms/leap/parser.go index 53d615a90..ed10d81bf 100644 --- a/platforms/leap/parser.go +++ b/platforms/leap/parser.go @@ -6,20 +6,20 @@ import ( // Gesture is a Leap Motion gesture that has been detected type Gesture struct { - Center []float64 `json:"center"` - Direction []float64 `json:"direction"` - Duration int `json:"duration"` - HandIDs []int `json:"handIds"` - ID int `json:"id"` - Normal []float64 `json:"normal"` - PointableIDs []int `json:"pointableIds"` - Position []float64 `json:"position"` - Progress float64 `json:"progress"` - Radius float64 `json:"radius"` - Speed float64 `json:"speed"` - StartPosition []float64 `json:"StartPosition"` - State string `json:"state"` - Type string `json:"type"` + Center []float64 `json:"center"` + Direction []float64 `json:"direction"` + Duration int `json:"duration"` + HandIDs []int `json:"handIds"` + ID int `json:"id"` + Normal []float64 `json:"normal"` + PointableIDs []int `json:"pointableIds"` + Position []float64 `json:"position"` + Progress float64 `json:"progress"` + Radius float64 `json:"radius"` + Speed float64 `json:"speed"` + StartPosition []float64 `json:"StartPosition"` + State string `json:"state"` + Type string `json:"type"` } // Hand is a Leap Motion hand that has been detected @@ -48,26 +48,26 @@ type Hand struct { // Pointable is a Leap Motion pointing motion that has been detected type Pointable struct { - Bases [][][]float64 `json:"bases"` - BTipPosition []float64 `json:"btipPosition"` - CarpPosition []float64 `json:"carpPosition"` - DipPosition []float64 `json:"dipPosition"` - Direction []float64 `json:"direction"` - Extended bool `json:"extended"` - HandID int `json:"handId"` - ID int `json:"id"` - Length float64 `json:"length"` - MCPPosition []float64 `json:"mcpPosition"` - PIPPosition []float64 `json:"pipPosition"` - StabilizedTipPosition []float64 `json:"stabilizedTipPosition"` - TimeVisible float64 `json:"timeVisible"` - TipPosition []float64 `json:"tipPosition"` - TipVelocity []float64 `json:"tipVelocity"` - Tool bool `json:"tool"` - TouchDistance float64 `json:"touchDistance"` - TouchZone string `json:"touchZone"` - Type int `json:"type"` - Width float64 `json:"width"` + Bases [][][]float64 `json:"bases"` + BTipPosition []float64 `json:"btipPosition"` + CarpPosition []float64 `json:"carpPosition"` + DipPosition []float64 `json:"dipPosition"` + Direction []float64 `json:"direction"` + Extended bool `json:"extended"` + HandID int `json:"handId"` + ID int `json:"id"` + Length float64 `json:"length"` + MCPPosition []float64 `json:"mcpPosition"` + PIPPosition []float64 `json:"pipPosition"` + StabilizedTipPosition []float64 `json:"stabilizedTipPosition"` + TimeVisible float64 `json:"timeVisible"` + TipPosition []float64 `json:"tipPosition"` + TipVelocity []float64 `json:"tipVelocity"` + Tool bool `json:"tool"` + TouchDistance float64 `json:"touchDistance"` + TouchZone string `json:"touchZone"` + Type int `json:"type"` + Width float64 `json:"width"` } // InteractionBox is the area within which the gestural interaction has been detected @@ -106,8 +106,8 @@ func (h *Hand) Z() float64 { } // ParseFrame converts json data to a Frame -func (l *Driver) ParseFrame(data []byte) Frame { +func (l *Driver) ParseFrame(data []byte) (Frame, error) { var frame Frame - json.Unmarshal(data, &frame) - return frame + err := json.Unmarshal(data, &frame) + return frame, err } diff --git a/platforms/mavlink/common/common.go b/platforms/mavlink/common/common.go index 3ef977e2b..9b624b29c 100644 --- a/platforms/mavlink/common/common.go +++ b/platforms/mavlink/common/common.go @@ -1,3 +1,4 @@ +//nolint:errcheck // to much code to fix it immediately package mavlink // @@ -634,7 +635,6 @@ const ( MAV_DISTANCE_SENSOR_ENUM_END = 2 // | ) -// // MESSAGE HEARTBEAT // // MAVLINK_MSG_ID_HEARTBEAT 0 @@ -642,8 +642,6 @@ const ( // MAVLINK_MSG_ID_HEARTBEAT_LEN 9 // // MAVLINK_MSG_ID_HEARTBEAT_CRC 50 -// -// type Heartbeat struct { CUSTOM_MODE uint32 // A bitfield for use for autopilot-specific flags. TYPE uint8 // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) @@ -703,7 +701,6 @@ func (m *Heartbeat) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.MAVLINK_VERSION) } -// // MESSAGE SYS_STATUS // // MAVLINK_MSG_ID_SYS_STATUS 1 @@ -711,8 +708,6 @@ func (m *Heartbeat) Decode(buf []byte) { // MAVLINK_MSG_ID_SYS_STATUS_LEN 31 // // MAVLINK_MSG_ID_SYS_STATUS_CRC 124 -// -// type SysStatus struct { ONBOARD_CONTROL_SENSORS_PRESENT uint32 // Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR ONBOARD_CONTROL_SENSORS_ENABLED uint32 // Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR @@ -800,7 +795,6 @@ func (m *SysStatus) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.BATTERY_REMAINING) } -// // MESSAGE SYSTEM_TIME // // MAVLINK_MSG_ID_SYSTEM_TIME 2 @@ -808,8 +802,6 @@ func (m *SysStatus) Decode(buf []byte) { // MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12 // // MAVLINK_MSG_ID_SYSTEM_TIME_CRC 137 -// -// type SystemTime struct { TIME_UNIX_USEC uint64 // Timestamp of the master clock in microseconds since UNIX epoch. TIME_BOOT_MS uint32 // Timestamp of the component clock since boot time in milliseconds. @@ -853,7 +845,6 @@ func (m *SystemTime) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TIME_BOOT_MS) } -// // MESSAGE PING // // MAVLINK_MSG_ID_PING 4 @@ -861,8 +852,6 @@ func (m *SystemTime) Decode(buf []byte) { // MAVLINK_MSG_ID_PING_LEN 14 // // MAVLINK_MSG_ID_PING_CRC 237 -// -// type Ping struct { TIME_USEC uint64 // Unix timestamp in microseconds SEQ uint32 // PING sequence @@ -914,7 +903,6 @@ func (m *Ping) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE CHANGE_OPERATOR_CONTROL // // MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5 @@ -922,8 +910,6 @@ func (m *Ping) Decode(buf []byte) { // MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28 // // MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC 217 -// -// type ChangeOperatorControl struct { TARGET_SYSTEM uint8 // System the GCS requests control for CONTROL_REQUEST uint8 // 0: request control of this MAV, 1: Release control of this MAV @@ -979,7 +965,6 @@ const ( MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_passkey_LEN = 25 ) -// // MESSAGE CHANGE_OPERATOR_CONTROL_ACK // // MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6 @@ -987,8 +972,6 @@ const ( // MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3 // // MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC 104 -// -// type ChangeOperatorControlAck struct { GCS_SYSTEM_ID uint8 // ID of the GCS this message CONTROL_REQUEST uint8 // 0: request control of this MAV, 1: Release control of this MAV @@ -1036,7 +1019,6 @@ func (m *ChangeOperatorControlAck) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.ACK) } -// // MESSAGE AUTH_KEY // // MAVLINK_MSG_ID_AUTH_KEY 7 @@ -1044,8 +1026,6 @@ func (m *ChangeOperatorControlAck) Decode(buf []byte) { // MAVLINK_MSG_ID_AUTH_KEY_LEN 32 // // MAVLINK_MSG_ID_AUTH_KEY_CRC 119 -// -// type AuthKey struct { KEY [32]uint8 // key } @@ -1089,7 +1069,6 @@ const ( MAVLINK_MSG_AUTH_KEY_FIELD_key_LEN = 32 ) -// // MESSAGE SET_MODE // // MAVLINK_MSG_ID_SET_MODE 11 @@ -1097,8 +1076,6 @@ const ( // MAVLINK_MSG_ID_SET_MODE_LEN 6 // // MAVLINK_MSG_ID_SET_MODE_CRC 89 -// -// type SetMode struct { CUSTOM_MODE uint32 // The new autopilot-specific mode. This field can be ignored by an autopilot. TARGET_SYSTEM uint8 // The system setting the mode @@ -1146,7 +1123,6 @@ func (m *SetMode) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.BASE_MODE) } -// // MESSAGE PARAM_REQUEST_READ // // MAVLINK_MSG_ID_PARAM_REQUEST_READ 20 @@ -1154,8 +1130,6 @@ func (m *SetMode) Decode(buf []byte) { // MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20 // // MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC 214 -// -// type ParamRequestRead struct { PARAM_INDEX int16 // Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) TARGET_SYSTEM uint8 // System ID @@ -1211,7 +1185,6 @@ const ( MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_param_id_LEN = 16 ) -// // MESSAGE PARAM_REQUEST_LIST // // MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21 @@ -1219,8 +1192,6 @@ const ( // MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2 // // MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC 159 -// -// type ParamRequestList struct { TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID @@ -1264,7 +1235,6 @@ func (m *ParamRequestList) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE PARAM_VALUE // // MAVLINK_MSG_ID_PARAM_VALUE 22 @@ -1272,8 +1242,6 @@ func (m *ParamRequestList) Decode(buf []byte) { // MAVLINK_MSG_ID_PARAM_VALUE_LEN 25 // // MAVLINK_MSG_ID_PARAM_VALUE_CRC 220 -// -// type ParamValue struct { PARAM_VALUE float32 // Onboard parameter value PARAM_COUNT uint16 // Total number of onboard parameters @@ -1333,7 +1301,6 @@ const ( MAVLINK_MSG_PARAM_VALUE_FIELD_param_id_LEN = 16 ) -// // MESSAGE PARAM_SET // // MAVLINK_MSG_ID_PARAM_SET 23 @@ -1341,8 +1308,6 @@ const ( // MAVLINK_MSG_ID_PARAM_SET_LEN 23 // // MAVLINK_MSG_ID_PARAM_SET_CRC 168 -// -// type ParamSet struct { PARAM_VALUE float32 // Onboard parameter value TARGET_SYSTEM uint8 // System ID @@ -1402,7 +1367,6 @@ const ( MAVLINK_MSG_PARAM_SET_FIELD_param_id_LEN = 16 ) -// // MESSAGE GPS_RAW_INT // // MAVLINK_MSG_ID_GPS_RAW_INT 24 @@ -1410,8 +1374,6 @@ const ( // MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30 // // MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24 -// -// type GpsRawInt struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) LAT int32 // Latitude (WGS84), in degrees * 1E7 @@ -1487,7 +1449,6 @@ func (m *GpsRawInt) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.SATELLITES_VISIBLE) } -// // MESSAGE GPS_STATUS // // MAVLINK_MSG_ID_GPS_STATUS 25 @@ -1495,8 +1456,6 @@ func (m *GpsRawInt) Decode(buf []byte) { // MAVLINK_MSG_ID_GPS_STATUS_LEN 101 // // MAVLINK_MSG_ID_GPS_STATUS_CRC 23 -// -// type GpsStatus struct { SATELLITES_VISIBLE uint8 // Number of satellites visible SATELLITE_PRN [20]uint8 // Global satellite ID @@ -1564,7 +1523,6 @@ const ( MAVLINK_MSG_GPS_STATUS_FIELD_satellite_snr_LEN = 20 ) -// // MESSAGE SCALED_IMU // // MAVLINK_MSG_ID_SCALED_IMU 26 @@ -1572,8 +1530,6 @@ const ( // MAVLINK_MSG_ID_SCALED_IMU_LEN 22 // // MAVLINK_MSG_ID_SCALED_IMU_CRC 170 -// -// type ScaledImu struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) XACC int16 // X acceleration (mg) @@ -1649,7 +1605,6 @@ func (m *ScaledImu) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.ZMAG) } -// // MESSAGE RAW_IMU // // MAVLINK_MSG_ID_RAW_IMU 27 @@ -1657,8 +1612,6 @@ func (m *ScaledImu) Decode(buf []byte) { // MAVLINK_MSG_ID_RAW_IMU_LEN 26 // // MAVLINK_MSG_ID_RAW_IMU_CRC 144 -// -// type RawImu struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) XACC int16 // X acceleration (raw) @@ -1734,7 +1687,6 @@ func (m *RawImu) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.ZMAG) } -// // MESSAGE RAW_PRESSURE // // MAVLINK_MSG_ID_RAW_PRESSURE 28 @@ -1742,8 +1694,6 @@ func (m *RawImu) Decode(buf []byte) { // MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16 // // MAVLINK_MSG_ID_RAW_PRESSURE_CRC 67 -// -// type RawPressure struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) PRESS_ABS int16 // Absolute pressure (raw) @@ -1799,7 +1749,6 @@ func (m *RawPressure) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TEMPERATURE) } -// // MESSAGE SCALED_PRESSURE // // MAVLINK_MSG_ID_SCALED_PRESSURE 29 @@ -1807,8 +1756,6 @@ func (m *RawPressure) Decode(buf []byte) { // MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 14 // // MAVLINK_MSG_ID_SCALED_PRESSURE_CRC 115 -// -// type ScaledPressure struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) PRESS_ABS float32 // Absolute pressure (hectopascal) @@ -1860,7 +1807,6 @@ func (m *ScaledPressure) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TEMPERATURE) } -// // MESSAGE ATTITUDE // // MAVLINK_MSG_ID_ATTITUDE 30 @@ -1868,8 +1814,6 @@ func (m *ScaledPressure) Decode(buf []byte) { // MAVLINK_MSG_ID_ATTITUDE_LEN 28 // // MAVLINK_MSG_ID_ATTITUDE_CRC 39 -// -// type Attitude struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) ROLL float32 // Roll angle (rad, -pi..+pi) @@ -1933,7 +1877,6 @@ func (m *Attitude) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.YAWSPEED) } -// // MESSAGE ATTITUDE_QUATERNION // // MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31 @@ -1941,8 +1884,6 @@ func (m *Attitude) Decode(buf []byte) { // MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32 // // MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246 -// -// type AttitudeQuaternion struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) Q1 float32 // Quaternion component 1, w (1 in null-rotation) @@ -2010,7 +1951,6 @@ func (m *AttitudeQuaternion) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.YAWSPEED) } -// // MESSAGE LOCAL_POSITION_NED // // MAVLINK_MSG_ID_LOCAL_POSITION_NED 32 @@ -2018,8 +1958,6 @@ func (m *AttitudeQuaternion) Decode(buf []byte) { // MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28 // // MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC 185 -// -// type LocalPositionNed struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) X float32 // X Position @@ -2083,7 +2021,6 @@ func (m *LocalPositionNed) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.VZ) } -// // MESSAGE GLOBAL_POSITION_INT // // MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33 @@ -2091,8 +2028,6 @@ func (m *LocalPositionNed) Decode(buf []byte) { // MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28 // // MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104 -// -// type GlobalPositionInt struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) LAT int32 // Latitude, expressed as * 1E7 @@ -2164,7 +2099,6 @@ func (m *GlobalPositionInt) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.HDG) } -// // MESSAGE RC_CHANNELS_SCALED // // MAVLINK_MSG_ID_RC_CHANNELS_SCALED 34 @@ -2172,8 +2106,6 @@ func (m *GlobalPositionInt) Decode(buf []byte) { // MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22 // // MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC 237 -// -// type RcChannelsScaled struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) CHAN1_SCALED int16 // RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. @@ -2253,7 +2185,6 @@ func (m *RcChannelsScaled) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.RSSI) } -// // MESSAGE RC_CHANNELS_RAW // // MAVLINK_MSG_ID_RC_CHANNELS_RAW 35 @@ -2261,8 +2192,6 @@ func (m *RcChannelsScaled) Decode(buf []byte) { // MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22 // // MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC 244 -// -// type RcChannelsRaw struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) CHAN1_RAW uint16 // RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. @@ -2342,7 +2271,6 @@ func (m *RcChannelsRaw) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.RSSI) } -// // MESSAGE SERVO_OUTPUT_RAW // // MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 36 @@ -2350,8 +2278,6 @@ func (m *RcChannelsRaw) Decode(buf []byte) { // MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 21 // // MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC 222 -// -// type ServoOutputRaw struct { TIME_USEC uint32 // Timestamp (microseconds since system boot) SERVO1_RAW uint16 // Servo output 1 value, in microseconds @@ -2427,7 +2353,6 @@ func (m *ServoOutputRaw) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.PORT) } -// // MESSAGE MISSION_REQUEST_PARTIAL_LIST // // MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST 37 @@ -2435,8 +2360,6 @@ func (m *ServoOutputRaw) Decode(buf []byte) { // MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 6 // // MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC 212 -// -// type MissionRequestPartialList struct { START_INDEX int16 // Start index, 0 by default END_INDEX int16 // End index, -1 by default (-1: send list to end). Else a valid index of the list @@ -2488,7 +2411,6 @@ func (m *MissionRequestPartialList) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE MISSION_WRITE_PARTIAL_LIST // // MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST 38 @@ -2496,8 +2418,6 @@ func (m *MissionRequestPartialList) Decode(buf []byte) { // MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 6 // // MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC 9 -// -// type MissionWritePartialList struct { START_INDEX int16 // Start index, 0 by default and smaller / equal to the largest index of the current onboard list. END_INDEX int16 // End index, equal or greater than start index. @@ -2549,7 +2469,6 @@ func (m *MissionWritePartialList) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE MISSION_ITEM // // MAVLINK_MSG_ID_MISSION_ITEM 39 @@ -2557,8 +2476,6 @@ func (m *MissionWritePartialList) Decode(buf []byte) { // MAVLINK_MSG_ID_MISSION_ITEM_LEN 37 // // MAVLINK_MSG_ID_MISSION_ITEM_CRC 254 -// -// type MissionItem struct { PARAM1 float32 // PARAM1, see MAV_CMD enum PARAM2 float32 // PARAM2, see MAV_CMD enum @@ -2650,7 +2567,6 @@ func (m *MissionItem) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.AUTOCONTINUE) } -// // MESSAGE MISSION_REQUEST // // MAVLINK_MSG_ID_MISSION_REQUEST 40 @@ -2658,8 +2574,6 @@ func (m *MissionItem) Decode(buf []byte) { // MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4 // // MAVLINK_MSG_ID_MISSION_REQUEST_CRC 230 -// -// type MissionRequest struct { SEQ uint16 // Sequence TARGET_SYSTEM uint8 // System ID @@ -2707,7 +2621,6 @@ func (m *MissionRequest) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE MISSION_SET_CURRENT // // MAVLINK_MSG_ID_MISSION_SET_CURRENT 41 @@ -2715,8 +2628,6 @@ func (m *MissionRequest) Decode(buf []byte) { // MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN 4 // // MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC 28 -// -// type MissionSetCurrent struct { SEQ uint16 // Sequence TARGET_SYSTEM uint8 // System ID @@ -2764,7 +2675,6 @@ func (m *MissionSetCurrent) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE MISSION_CURRENT // // MAVLINK_MSG_ID_MISSION_CURRENT 42 @@ -2772,8 +2682,6 @@ func (m *MissionSetCurrent) Decode(buf []byte) { // MAVLINK_MSG_ID_MISSION_CURRENT_LEN 2 // // MAVLINK_MSG_ID_MISSION_CURRENT_CRC 28 -// -// type MissionCurrent struct { SEQ uint16 // Sequence } @@ -2813,7 +2721,6 @@ func (m *MissionCurrent) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.SEQ) } -// // MESSAGE MISSION_REQUEST_LIST // // MAVLINK_MSG_ID_MISSION_REQUEST_LIST 43 @@ -2821,8 +2728,6 @@ func (m *MissionCurrent) Decode(buf []byte) { // MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 2 // // MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC 132 -// -// type MissionRequestList struct { TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID @@ -2866,7 +2771,6 @@ func (m *MissionRequestList) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE MISSION_COUNT // // MAVLINK_MSG_ID_MISSION_COUNT 44 @@ -2874,8 +2778,6 @@ func (m *MissionRequestList) Decode(buf []byte) { // MAVLINK_MSG_ID_MISSION_COUNT_LEN 4 // // MAVLINK_MSG_ID_MISSION_COUNT_CRC 221 -// -// type MissionCount struct { COUNT uint16 // Number of mission items in the sequence TARGET_SYSTEM uint8 // System ID @@ -2923,7 +2825,6 @@ func (m *MissionCount) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE MISSION_CLEAR_ALL // // MAVLINK_MSG_ID_MISSION_CLEAR_ALL 45 @@ -2931,8 +2832,6 @@ func (m *MissionCount) Decode(buf []byte) { // MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 2 // // MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC 232 -// -// type MissionClearAll struct { TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID @@ -2976,7 +2875,6 @@ func (m *MissionClearAll) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE MISSION_ITEM_REACHED // // MAVLINK_MSG_ID_MISSION_ITEM_REACHED 46 @@ -2984,8 +2882,6 @@ func (m *MissionClearAll) Decode(buf []byte) { // MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN 2 // // MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC 11 -// -// type MissionItemReached struct { SEQ uint16 // Sequence } @@ -3025,7 +2921,6 @@ func (m *MissionItemReached) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.SEQ) } -// // MESSAGE MISSION_ACK // // MAVLINK_MSG_ID_MISSION_ACK 47 @@ -3033,8 +2928,6 @@ func (m *MissionItemReached) Decode(buf []byte) { // MAVLINK_MSG_ID_MISSION_ACK_LEN 3 // // MAVLINK_MSG_ID_MISSION_ACK_CRC 153 -// -// type MissionAck struct { TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID @@ -3082,7 +2975,6 @@ func (m *MissionAck) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TYPE) } -// // MESSAGE SET_GPS_GLOBAL_ORIGIN // // MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN 48 @@ -3090,8 +2982,6 @@ func (m *MissionAck) Decode(buf []byte) { // MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN 13 // // MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC 41 -// -// type SetGpsGlobalOrigin struct { LATITUDE int32 // Latitude (WGS84), in degrees * 1E7 LONGITUDE int32 // Longitude (WGS84, in degrees * 1E7 @@ -3143,7 +3033,6 @@ func (m *SetGpsGlobalOrigin) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) } -// // MESSAGE GPS_GLOBAL_ORIGIN // // MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49 @@ -3151,8 +3040,6 @@ func (m *SetGpsGlobalOrigin) Decode(buf []byte) { // MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12 // // MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC 39 -// -// type GpsGlobalOrigin struct { LATITUDE int32 // Latitude (WGS84), in degrees * 1E7 LONGITUDE int32 // Longitude (WGS84), in degrees * 1E7 @@ -3200,7 +3087,6 @@ func (m *GpsGlobalOrigin) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.ALTITUDE) } -// // MESSAGE SET_LOCAL_POSITION_SETPOINT // // MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT 50 @@ -3208,8 +3094,6 @@ func (m *GpsGlobalOrigin) Decode(buf []byte) { // MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN 19 // // MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC 214 -// -// type SetLocalPositionSetpoint struct { X float32 // x position Y float32 // y position @@ -3273,7 +3157,6 @@ func (m *SetLocalPositionSetpoint) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.COORDINATE_FRAME) } -// // MESSAGE LOCAL_POSITION_SETPOINT // // MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT 51 @@ -3281,8 +3164,6 @@ func (m *SetLocalPositionSetpoint) Decode(buf []byte) { // MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN 17 // // MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC 223 -// -// type LocalPositionSetpoint struct { X float32 // x position Y float32 // y position @@ -3338,7 +3219,6 @@ func (m *LocalPositionSetpoint) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.COORDINATE_FRAME) } -// // MESSAGE GLOBAL_POSITION_SETPOINT_INT // // MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT 52 @@ -3346,8 +3226,6 @@ func (m *LocalPositionSetpoint) Decode(buf []byte) { // MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN 15 // // MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC 141 -// -// type GlobalPositionSetpointInt struct { LATITUDE int32 // Latitude (WGS84), in degrees * 1E7 LONGITUDE int32 // Longitude (WGS84), in degrees * 1E7 @@ -3403,7 +3281,6 @@ func (m *GlobalPositionSetpointInt) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.COORDINATE_FRAME) } -// // MESSAGE SET_GLOBAL_POSITION_SETPOINT_INT // // MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT 53 @@ -3411,8 +3288,6 @@ func (m *GlobalPositionSetpointInt) Decode(buf []byte) { // MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN 15 // // MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC 33 -// -// type SetGlobalPositionSetpointInt struct { LATITUDE int32 // Latitude (WGS84), in degrees * 1E7 LONGITUDE int32 // Longitude (WGS84), in degrees * 1E7 @@ -3468,7 +3343,6 @@ func (m *SetGlobalPositionSetpointInt) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.COORDINATE_FRAME) } -// // MESSAGE SAFETY_SET_ALLOWED_AREA // // MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54 @@ -3476,8 +3350,6 @@ func (m *SetGlobalPositionSetpointInt) Decode(buf []byte) { // MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27 // // MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC 15 -// -// type SafetySetAllowedArea struct { P1X float32 // x position 1 / Latitude 1 P1Y float32 // y position 1 / Longitude 1 @@ -3549,7 +3421,6 @@ func (m *SafetySetAllowedArea) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.FRAME) } -// // MESSAGE SAFETY_ALLOWED_AREA // // MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55 @@ -3557,8 +3428,6 @@ func (m *SafetySetAllowedArea) Decode(buf []byte) { // MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25 // // MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC 3 -// -// type SafetyAllowedArea struct { P1X float32 // x position 1 / Latitude 1 P1Y float32 // y position 1 / Longitude 1 @@ -3622,7 +3491,6 @@ func (m *SafetyAllowedArea) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.FRAME) } -// // MESSAGE SET_ROLL_PITCH_YAW_THRUST // // MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST 56 @@ -3630,8 +3498,6 @@ func (m *SafetyAllowedArea) Decode(buf []byte) { // MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN 18 // // MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC 100 -// -// type SetRollPitchYawThrust struct { ROLL float32 // Desired roll angle in radians PITCH float32 // Desired pitch angle in radians @@ -3691,7 +3557,6 @@ func (m *SetRollPitchYawThrust) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST // // MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST 57 @@ -3699,8 +3564,6 @@ func (m *SetRollPitchYawThrust) Decode(buf []byte) { // MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN 18 // // MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC 24 -// -// type SetRollPitchYawSpeedThrust struct { ROLL_SPEED float32 // Desired roll angular speed in rad/s PITCH_SPEED float32 // Desired pitch angular speed in rad/s @@ -3760,7 +3623,6 @@ func (m *SetRollPitchYawSpeedThrust) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT // // MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT 58 @@ -3768,8 +3630,6 @@ func (m *SetRollPitchYawSpeedThrust) Decode(buf []byte) { // MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN 20 // // MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC 239 -// -// type RollPitchYawThrustSetpoint struct { TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot ROLL float32 // Desired roll angle in radians @@ -3825,7 +3685,6 @@ func (m *RollPitchYawThrustSetpoint) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.THRUST) } -// // MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT // // MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT 59 @@ -3833,8 +3692,6 @@ func (m *RollPitchYawThrustSetpoint) Decode(buf []byte) { // MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN 20 // // MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC 238 -// -// type RollPitchYawSpeedThrustSetpoint struct { TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot ROLL_SPEED float32 // Desired roll angular speed in rad/s @@ -3890,7 +3747,6 @@ func (m *RollPitchYawSpeedThrustSetpoint) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.THRUST) } -// // MESSAGE SET_QUAD_MOTORS_SETPOINT // // MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT 60 @@ -3898,8 +3754,6 @@ func (m *RollPitchYawSpeedThrustSetpoint) Decode(buf []byte) { // MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN 9 // // MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC 30 -// -// type SetQuadMotorsSetpoint struct { MOTOR_FRONT_NW uint16 // Front motor in + configuration, front left motor in x configuration MOTOR_RIGHT_NE uint16 // Right motor in + configuration, front right motor in x configuration @@ -3955,7 +3809,6 @@ func (m *SetQuadMotorsSetpoint) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) } -// // MESSAGE SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST // // MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST 61 @@ -3963,8 +3816,6 @@ func (m *SetQuadMotorsSetpoint) Decode(buf []byte) { // MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN 34 // // MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC 240 -// -// type SetQuadSwarmRollPitchYawThrust struct { ROLL [4]int16 // Desired roll angle in radians +-PI (+-INT16_MAX) PITCH [4]int16 // Desired pitch angle in radians +-PI (+-INT16_MAX) @@ -4031,7 +3882,6 @@ const ( MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_thrust_LEN = 4 ) -// // MESSAGE NAV_CONTROLLER_OUTPUT // // MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62 @@ -4039,8 +3889,6 @@ const ( // MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26 // // MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC 183 -// -// type NavControllerOutput struct { NAV_ROLL float32 // Current desired roll in degrees NAV_PITCH float32 // Current desired pitch in degrees @@ -4108,7 +3956,6 @@ func (m *NavControllerOutput) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.WP_DIST) } -// // MESSAGE SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST // // MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST 63 @@ -4116,8 +3963,6 @@ func (m *NavControllerOutput) Decode(buf []byte) { // MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN 46 // // MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC 130 -// -// type SetQuadSwarmLedRollPitchYawThrust struct { ROLL [4]int16 // Desired roll angle in radians +-PI (+-INT16_MAX) PITCH [4]int16 // Desired pitch angle in radians +-PI (+-INT16_MAX) @@ -4199,7 +4044,6 @@ const ( MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_led_green_LEN = 4 ) -// // MESSAGE STATE_CORRECTION // // MAVLINK_MSG_ID_STATE_CORRECTION 64 @@ -4207,8 +4051,6 @@ const ( // MAVLINK_MSG_ID_STATE_CORRECTION_LEN 36 // // MAVLINK_MSG_ID_STATE_CORRECTION_CRC 130 -// -// type StateCorrection struct { XERR float32 // x position error YERR float32 // y position error @@ -4280,7 +4122,6 @@ func (m *StateCorrection) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.VZERR) } -// // MESSAGE RC_CHANNELS // // MAVLINK_MSG_ID_RC_CHANNELS 65 @@ -4288,8 +4129,6 @@ func (m *StateCorrection) Decode(buf []byte) { // MAVLINK_MSG_ID_RC_CHANNELS_LEN 42 // // MAVLINK_MSG_ID_RC_CHANNELS_CRC 118 -// -// type RcChannels struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) CHAN1_RAW uint16 // RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. @@ -4409,7 +4248,6 @@ func (m *RcChannels) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.RSSI) } -// // MESSAGE REQUEST_DATA_STREAM // // MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66 @@ -4417,8 +4255,6 @@ func (m *RcChannels) Decode(buf []byte) { // MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6 // // MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC 148 -// -// type RequestDataStream struct { REQ_MESSAGE_RATE uint16 // The requested interval between two messages of this type TARGET_SYSTEM uint8 // The target requested to send the message stream. @@ -4474,7 +4310,6 @@ func (m *RequestDataStream) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.START_STOP) } -// // MESSAGE DATA_STREAM // // MAVLINK_MSG_ID_DATA_STREAM 67 @@ -4482,8 +4317,6 @@ func (m *RequestDataStream) Decode(buf []byte) { // MAVLINK_MSG_ID_DATA_STREAM_LEN 4 // // MAVLINK_MSG_ID_DATA_STREAM_CRC 21 -// -// type DataStream struct { MESSAGE_RATE uint16 // The requested interval between two messages of this type STREAM_ID uint8 // The ID of the requested data stream @@ -4531,7 +4364,6 @@ func (m *DataStream) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.ON_OFF) } -// // MESSAGE MANUAL_CONTROL // // MAVLINK_MSG_ID_MANUAL_CONTROL 69 @@ -4539,8 +4371,6 @@ func (m *DataStream) Decode(buf []byte) { // MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 11 // // MAVLINK_MSG_ID_MANUAL_CONTROL_CRC 243 -// -// type ManualControl struct { X int16 // X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. Y int16 // Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. @@ -4600,7 +4430,6 @@ func (m *ManualControl) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET) } -// // MESSAGE RC_CHANNELS_OVERRIDE // // MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70 @@ -4608,8 +4437,6 @@ func (m *ManualControl) Decode(buf []byte) { // MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18 // // MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC 124 -// -// type RcChannelsOverride struct { CHAN1_RAW uint16 // RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. CHAN2_RAW uint16 // RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. @@ -4685,7 +4512,6 @@ func (m *RcChannelsOverride) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE VFR_HUD // // MAVLINK_MSG_ID_VFR_HUD 74 @@ -4693,8 +4519,6 @@ func (m *RcChannelsOverride) Decode(buf []byte) { // MAVLINK_MSG_ID_VFR_HUD_LEN 20 // // MAVLINK_MSG_ID_VFR_HUD_CRC 20 -// -// type VfrHud struct { AIRSPEED float32 // Current airspeed in m/s GROUNDSPEED float32 // Current ground speed in m/s @@ -4754,7 +4578,6 @@ func (m *VfrHud) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.THROTTLE) } -// // MESSAGE COMMAND_LONG // // MAVLINK_MSG_ID_COMMAND_LONG 76 @@ -4762,8 +4585,6 @@ func (m *VfrHud) Decode(buf []byte) { // MAVLINK_MSG_ID_COMMAND_LONG_LEN 33 // // MAVLINK_MSG_ID_COMMAND_LONG_CRC 152 -// -// type CommandLong struct { PARAM1 float32 // Parameter 1, as defined by MAV_CMD enum. PARAM2 float32 // Parameter 2, as defined by MAV_CMD enum. @@ -4843,7 +4664,6 @@ func (m *CommandLong) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.CONFIRMATION) } -// // MESSAGE COMMAND_ACK // // MAVLINK_MSG_ID_COMMAND_ACK 77 @@ -4851,8 +4671,6 @@ func (m *CommandLong) Decode(buf []byte) { // MAVLINK_MSG_ID_COMMAND_ACK_LEN 3 // // MAVLINK_MSG_ID_COMMAND_ACK_CRC 143 -// -// type CommandAck struct { COMMAND uint16 // Command ID, as defined by MAV_CMD enum. RESULT uint8 // See MAV_RESULT enum @@ -4896,7 +4714,6 @@ func (m *CommandAck) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.RESULT) } -// // MESSAGE ROLL_PITCH_YAW_RATES_THRUST_SETPOINT // // MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT 80 @@ -4904,8 +4721,6 @@ func (m *CommandAck) Decode(buf []byte) { // MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN 20 // // MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC 127 -// -// type RollPitchYawRatesThrustSetpoint struct { TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot ROLL_RATE float32 // Desired roll rate in radians per second @@ -4961,7 +4776,6 @@ func (m *RollPitchYawRatesThrustSetpoint) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.THRUST) } -// // MESSAGE MANUAL_SETPOINT // // MAVLINK_MSG_ID_MANUAL_SETPOINT 81 @@ -4969,8 +4783,6 @@ func (m *RollPitchYawRatesThrustSetpoint) Decode(buf []byte) { // MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22 // // MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC 106 -// -// type ManualSetpoint struct { TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot ROLL float32 // Desired roll rate in radians per second @@ -5034,7 +4846,6 @@ func (m *ManualSetpoint) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.MANUAL_OVERRIDE_SWITCH) } -// // MESSAGE ATTITUDE_SETPOINT_EXTERNAL // // MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL 82 @@ -5042,8 +4853,6 @@ func (m *ManualSetpoint) Decode(buf []byte) { // MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN 39 // // MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_CRC 147 -// -// type AttitudeSetpointExternal struct { TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot Q [4]float32 // Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) @@ -5119,7 +4928,6 @@ const ( MAVLINK_MSG_ATTITUDE_SETPOINT_EXTERNAL_FIELD_q_LEN = 4 ) -// // MESSAGE LOCAL_NED_POSITION_SETPOINT_EXTERNAL // // MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL 83 @@ -5127,8 +4935,6 @@ const ( // MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN 45 // // MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_CRC 211 -// -// type LocalNedPositionSetpointExternal struct { TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot X float32 // X Position in NED frame in meters @@ -5220,7 +5026,6 @@ func (m *LocalNedPositionSetpointExternal) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.COORDINATE_FRAME) } -// // MESSAGE GLOBAL_POSITION_SETPOINT_EXTERNAL_INT // // MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT 84 @@ -5228,8 +5033,6 @@ func (m *LocalNedPositionSetpointExternal) Decode(buf []byte) { // MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN 44 // // MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_CRC 198 -// -// type GlobalPositionSetpointExternalInt struct { TIME_BOOT_MS uint32 // Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. LAT_INT int32 // X Position in WGS84 frame in 1e7 * meters @@ -5317,7 +5120,6 @@ func (m *GlobalPositionSetpointExternalInt) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET // // MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET 89 @@ -5325,8 +5127,6 @@ func (m *GlobalPositionSetpointExternalInt) Decode(buf []byte) { // MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN 28 // // MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC 231 -// -// type LocalPositionNedSystemGlobalOffset struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) X float32 // X Position @@ -5390,7 +5190,6 @@ func (m *LocalPositionNedSystemGlobalOffset) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.YAW) } -// // MESSAGE HIL_STATE // // MAVLINK_MSG_ID_HIL_STATE 90 @@ -5398,8 +5197,6 @@ func (m *LocalPositionNedSystemGlobalOffset) Decode(buf []byte) { // MAVLINK_MSG_ID_HIL_STATE_LEN 56 // // MAVLINK_MSG_ID_HIL_STATE_CRC 183 -// -// type HilState struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) ROLL float32 // Roll angle (rad) @@ -5499,7 +5296,6 @@ func (m *HilState) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.ZACC) } -// // MESSAGE HIL_CONTROLS // // MAVLINK_MSG_ID_HIL_CONTROLS 91 @@ -5507,8 +5303,6 @@ func (m *HilState) Decode(buf []byte) { // MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42 // // MAVLINK_MSG_ID_HIL_CONTROLS_CRC 63 -// -// type HilControls struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) ROLL_AILERONS float32 // Control output -1 .. 1 @@ -5588,7 +5382,6 @@ func (m *HilControls) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.NAV_MODE) } -// // MESSAGE HIL_RC_INPUTS_RAW // // MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW 92 @@ -5596,8 +5389,6 @@ func (m *HilControls) Decode(buf []byte) { // MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33 // // MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC 54 -// -// type HilRcInputsRaw struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) CHAN1_RAW uint16 // RC channel 1 value, in microseconds @@ -5689,7 +5480,6 @@ func (m *HilRcInputsRaw) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.RSSI) } -// // MESSAGE OPTICAL_FLOW // // MAVLINK_MSG_ID_OPTICAL_FLOW 100 @@ -5697,8 +5487,6 @@ func (m *HilRcInputsRaw) Decode(buf []byte) { // MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26 // // MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175 -// -// type OpticalFlow struct { TIME_USEC uint64 // Timestamp (UNIX) FLOW_COMP_M_X float32 // Flow in meters in x-sensor direction, angular-speed compensated @@ -5766,7 +5554,6 @@ func (m *OpticalFlow) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.QUALITY) } -// // MESSAGE GLOBAL_VISION_POSITION_ESTIMATE // // MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101 @@ -5774,8 +5561,6 @@ func (m *OpticalFlow) Decode(buf []byte) { // MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32 // // MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC 102 -// -// type GlobalVisionPositionEstimate struct { USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) X float32 // Global X position @@ -5839,7 +5624,6 @@ func (m *GlobalVisionPositionEstimate) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.YAW) } -// // MESSAGE VISION_POSITION_ESTIMATE // // MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 102 @@ -5847,8 +5631,6 @@ func (m *GlobalVisionPositionEstimate) Decode(buf []byte) { // MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32 // // MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC 158 -// -// type VisionPositionEstimate struct { USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) X float32 // Global X position @@ -5912,7 +5694,6 @@ func (m *VisionPositionEstimate) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.YAW) } -// // MESSAGE VISION_SPEED_ESTIMATE // // MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103 @@ -5920,8 +5701,6 @@ func (m *VisionPositionEstimate) Decode(buf []byte) { // MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20 // // MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC 208 -// -// type VisionSpeedEstimate struct { USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) X float32 // Global X speed @@ -5973,7 +5752,6 @@ func (m *VisionSpeedEstimate) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.Z) } -// // MESSAGE VICON_POSITION_ESTIMATE // // MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 104 @@ -5981,8 +5759,6 @@ func (m *VisionSpeedEstimate) Decode(buf []byte) { // MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32 // // MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC 56 -// -// type ViconPositionEstimate struct { USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) X float32 // Global X position @@ -6046,7 +5822,6 @@ func (m *ViconPositionEstimate) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.YAW) } -// // MESSAGE HIGHRES_IMU // // MAVLINK_MSG_ID_HIGHRES_IMU 105 @@ -6054,8 +5829,6 @@ func (m *ViconPositionEstimate) Decode(buf []byte) { // MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62 // // MAVLINK_MSG_ID_HIGHRES_IMU_CRC 93 -// -// type HighresImu struct { TIME_USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) XACC float32 // X acceleration (m/s^2) @@ -6151,7 +5924,6 @@ func (m *HighresImu) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.FIELDS_UPDATED) } -// // MESSAGE OMNIDIRECTIONAL_FLOW // // MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW 106 @@ -6159,8 +5931,6 @@ func (m *HighresImu) Decode(buf []byte) { // MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN 54 // // MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC 211 -// -// type OmnidirectionalFlow struct { TIME_USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) FRONT_DISTANCE_M float32 // Front distance in meters. Positive value (including zero): distance known. Negative value: Unknown distance @@ -6225,7 +5995,6 @@ const ( MAVLINK_MSG_OMNIDIRECTIONAL_FLOW_FIELD_right_LEN = 10 ) -// // MESSAGE HIL_SENSOR // // MAVLINK_MSG_ID_HIL_SENSOR 107 @@ -6233,8 +6002,6 @@ const ( // MAVLINK_MSG_ID_HIL_SENSOR_LEN 64 // // MAVLINK_MSG_ID_HIL_SENSOR_CRC 108 -// -// type HilSensor struct { TIME_USEC uint64 // Timestamp (microseconds, synced to UNIX time or since system boot) XACC float32 // X acceleration (m/s^2) @@ -6330,7 +6097,6 @@ func (m *HilSensor) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.FIELDS_UPDATED) } -// // MESSAGE SIM_STATE // // MAVLINK_MSG_ID_SIM_STATE 108 @@ -6338,8 +6104,6 @@ func (m *HilSensor) Decode(buf []byte) { // MAVLINK_MSG_ID_SIM_STATE_LEN 84 // // MAVLINK_MSG_ID_SIM_STATE_CRC 32 -// -// type SimState struct { Q1 float32 // True attitude quaternion component 1, w (1 in null-rotation) Q2 float32 // True attitude quaternion component 2, x (0 in null-rotation) @@ -6459,7 +6223,6 @@ func (m *SimState) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.VD) } -// // MESSAGE RADIO_STATUS // // MAVLINK_MSG_ID_RADIO_STATUS 109 @@ -6467,8 +6230,6 @@ func (m *SimState) Decode(buf []byte) { // MAVLINK_MSG_ID_RADIO_STATUS_LEN 9 // // MAVLINK_MSG_ID_RADIO_STATUS_CRC 185 -// -// type RadioStatus struct { RXERRORS uint16 // receive errors FIXED uint16 // count of error corrected packets @@ -6532,7 +6293,6 @@ func (m *RadioStatus) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.REMNOISE) } -// // MESSAGE FILE_TRANSFER_START // // MAVLINK_MSG_ID_FILE_TRANSFER_START 110 @@ -6540,8 +6300,6 @@ func (m *RadioStatus) Decode(buf []byte) { // MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN 254 // // MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC 235 -// -// type FileTransferStart struct { TRANSFER_UID uint64 // Unique transfer ID FILE_SIZE uint32 // File size in bytes @@ -6601,7 +6359,6 @@ const ( MAVLINK_MSG_FILE_TRANSFER_START_FIELD_dest_path_LEN = 240 ) -// // MESSAGE FILE_TRANSFER_DIR_LIST // // MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST 111 @@ -6609,8 +6366,6 @@ const ( // MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN 249 // // MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC 93 -// -// type FileTransferDirList struct { TRANSFER_UID uint64 // Unique transfer ID DIR_PATH [240]uint8 // Directory path to list @@ -6662,7 +6417,6 @@ const ( MAVLINK_MSG_FILE_TRANSFER_DIR_LIST_FIELD_dir_path_LEN = 240 ) -// // MESSAGE FILE_TRANSFER_RES // // MAVLINK_MSG_ID_FILE_TRANSFER_RES 112 @@ -6670,8 +6424,6 @@ const ( // MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN 9 // // MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC 124 -// -// type FileTransferRes struct { TRANSFER_UID uint64 // Unique transfer ID RESULT uint8 // 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device @@ -6715,7 +6467,6 @@ func (m *FileTransferRes) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.RESULT) } -// // MESSAGE HIL_GPS // // MAVLINK_MSG_ID_HIL_GPS 113 @@ -6723,8 +6474,6 @@ func (m *FileTransferRes) Decode(buf []byte) { // MAVLINK_MSG_ID_HIL_GPS_LEN 36 // // MAVLINK_MSG_ID_HIL_GPS_CRC 124 -// -// type HilGps struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) LAT int32 // Latitude (WGS84), in degrees * 1E7 @@ -6812,7 +6561,6 @@ func (m *HilGps) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.SATELLITES_VISIBLE) } -// // MESSAGE HIL_OPTICAL_FLOW // // MAVLINK_MSG_ID_HIL_OPTICAL_FLOW 114 @@ -6820,8 +6568,6 @@ func (m *HilGps) Decode(buf []byte) { // MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 26 // // MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC 119 -// -// type HilOpticalFlow struct { TIME_USEC uint64 // Timestamp (UNIX) FLOW_COMP_M_X float32 // Flow in meters in x-sensor direction, angular-speed compensated @@ -6889,7 +6635,6 @@ func (m *HilOpticalFlow) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.QUALITY) } -// // MESSAGE HIL_STATE_QUATERNION // // MAVLINK_MSG_ID_HIL_STATE_QUATERNION 115 @@ -6897,8 +6642,6 @@ func (m *HilOpticalFlow) Decode(buf []byte) { // MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN 64 // // MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC 4 -// -// type HilStateQuaternion struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) ATTITUDE_QUATERNION [4]float32 // Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) @@ -7002,7 +6745,6 @@ const ( MAVLINK_MSG_HIL_STATE_QUATERNION_FIELD_attitude_quaternion_LEN = 4 ) -// // MESSAGE SCALED_IMU2 // // MAVLINK_MSG_ID_SCALED_IMU2 116 @@ -7010,8 +6752,6 @@ const ( // MAVLINK_MSG_ID_SCALED_IMU2_LEN 22 // // MAVLINK_MSG_ID_SCALED_IMU2_CRC 76 -// -// type ScaledImu2 struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) XACC int16 // X acceleration (mg) @@ -7087,7 +6827,6 @@ func (m *ScaledImu2) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.ZMAG) } -// // MESSAGE LOG_REQUEST_LIST // // MAVLINK_MSG_ID_LOG_REQUEST_LIST 117 @@ -7095,8 +6834,6 @@ func (m *ScaledImu2) Decode(buf []byte) { // MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN 6 // // MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC 128 -// -// type LogRequestList struct { START uint16 // First log id (0 for first available) END uint16 // Last log id (0xffff for last available) @@ -7148,7 +6885,6 @@ func (m *LogRequestList) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE LOG_ENTRY // // MAVLINK_MSG_ID_LOG_ENTRY 118 @@ -7156,8 +6892,6 @@ func (m *LogRequestList) Decode(buf []byte) { // MAVLINK_MSG_ID_LOG_ENTRY_LEN 14 // // MAVLINK_MSG_ID_LOG_ENTRY_CRC 56 -// -// type LogEntry struct { TIME_UTC uint32 // UTC timestamp of log in seconds since 1970, or 0 if not available SIZE uint32 // Size of the log (may be approximate) in bytes @@ -7213,7 +6947,6 @@ func (m *LogEntry) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.LAST_LOG_NUM) } -// // MESSAGE LOG_REQUEST_DATA // // MAVLINK_MSG_ID_LOG_REQUEST_DATA 119 @@ -7221,8 +6954,6 @@ func (m *LogEntry) Decode(buf []byte) { // MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN 12 // // MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC 116 -// -// type LogRequestData struct { OFS uint32 // Offset into the log COUNT uint32 // Number of bytes @@ -7278,7 +7009,6 @@ func (m *LogRequestData) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE LOG_DATA // // MAVLINK_MSG_ID_LOG_DATA 120 @@ -7286,8 +7016,6 @@ func (m *LogRequestData) Decode(buf []byte) { // MAVLINK_MSG_ID_LOG_DATA_LEN 97 // // MAVLINK_MSG_ID_LOG_DATA_CRC 134 -// -// type LogData struct { OFS uint32 // Offset into the log ID uint16 // Log id (from LOG_ENTRY reply) @@ -7343,7 +7071,6 @@ const ( MAVLINK_MSG_LOG_DATA_FIELD_data_LEN = 90 ) -// // MESSAGE LOG_ERASE // // MAVLINK_MSG_ID_LOG_ERASE 121 @@ -7351,8 +7078,6 @@ const ( // MAVLINK_MSG_ID_LOG_ERASE_LEN 2 // // MAVLINK_MSG_ID_LOG_ERASE_CRC 237 -// -// type LogErase struct { TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID @@ -7396,7 +7121,6 @@ func (m *LogErase) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE LOG_REQUEST_END // // MAVLINK_MSG_ID_LOG_REQUEST_END 122 @@ -7404,8 +7128,6 @@ func (m *LogErase) Decode(buf []byte) { // MAVLINK_MSG_ID_LOG_REQUEST_END_LEN 2 // // MAVLINK_MSG_ID_LOG_REQUEST_END_CRC 203 -// -// type LogRequestEnd struct { TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID @@ -7449,7 +7171,6 @@ func (m *LogRequestEnd) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_COMPONENT) } -// // MESSAGE GPS_INJECT_DATA // // MAVLINK_MSG_ID_GPS_INJECT_DATA 123 @@ -7457,8 +7178,6 @@ func (m *LogRequestEnd) Decode(buf []byte) { // MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113 // // MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC 250 -// -// type GpsInjectData struct { TARGET_SYSTEM uint8 // System ID TARGET_COMPONENT uint8 // Component ID @@ -7514,7 +7233,6 @@ const ( MAVLINK_MSG_GPS_INJECT_DATA_FIELD_data_LEN = 110 ) -// // MESSAGE GPS2_RAW // // MAVLINK_MSG_ID_GPS2_RAW 124 @@ -7522,8 +7240,6 @@ const ( // MAVLINK_MSG_ID_GPS2_RAW_LEN 35 // // MAVLINK_MSG_ID_GPS2_RAW_CRC 87 -// -// type Gps2Raw struct { TIME_USEC uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot) LAT int32 // Latitude (WGS84), in degrees * 1E7 @@ -7607,7 +7323,6 @@ func (m *Gps2Raw) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.DGPS_NUMCH) } -// // MESSAGE POWER_STATUS // // MAVLINK_MSG_ID_POWER_STATUS 125 @@ -7615,8 +7330,6 @@ func (m *Gps2Raw) Decode(buf []byte) { // MAVLINK_MSG_ID_POWER_STATUS_LEN 6 // // MAVLINK_MSG_ID_POWER_STATUS_CRC 203 -// -// type PowerStatus struct { VCC uint16 // 5V rail voltage in millivolts VSERVO uint16 // servo rail voltage in millivolts @@ -7664,7 +7377,6 @@ func (m *PowerStatus) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.FLAGS) } -// // MESSAGE SERIAL_CONTROL // // MAVLINK_MSG_ID_SERIAL_CONTROL 126 @@ -7672,8 +7384,6 @@ func (m *PowerStatus) Decode(buf []byte) { // MAVLINK_MSG_ID_SERIAL_CONTROL_LEN 79 // // MAVLINK_MSG_ID_SERIAL_CONTROL_CRC 220 -// -// type SerialControl struct { BAUDRATE uint32 // Baudrate of transfer. Zero means no change. TIMEOUT uint16 // Timeout for reply data in milliseconds @@ -7737,7 +7447,6 @@ const ( MAVLINK_MSG_SERIAL_CONTROL_FIELD_data_LEN = 70 ) -// // MESSAGE GPS_RTK // // MAVLINK_MSG_ID_GPS_RTK 127 @@ -7745,8 +7454,6 @@ const ( // MAVLINK_MSG_ID_GPS_RTK_LEN 35 // // MAVLINK_MSG_ID_GPS_RTK_CRC 25 -// -// type GpsRtk struct { TIME_LAST_BASELINE_MS uint32 // Time since boot of last baseline message received in ms. TOW uint32 // GPS Time of Week of last baseline @@ -7834,7 +7541,6 @@ func (m *GpsRtk) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.BASELINE_COORDS_TYPE) } -// // MESSAGE GPS2_RTK // // MAVLINK_MSG_ID_GPS2_RTK 128 @@ -7842,8 +7548,6 @@ func (m *GpsRtk) Decode(buf []byte) { // MAVLINK_MSG_ID_GPS2_RTK_LEN 35 // // MAVLINK_MSG_ID_GPS2_RTK_CRC 226 -// -// type Gps2Rtk struct { TIME_LAST_BASELINE_MS uint32 // Time since boot of last baseline message received in ms. TOW uint32 // GPS Time of Week of last baseline @@ -7931,7 +7635,6 @@ func (m *Gps2Rtk) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.BASELINE_COORDS_TYPE) } -// // MESSAGE DATA_TRANSMISSION_HANDSHAKE // // MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 130 @@ -7939,8 +7642,6 @@ func (m *Gps2Rtk) Decode(buf []byte) { // MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 13 // // MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC 29 -// -// type DataTransmissionHandshake struct { SIZE uint32 // total data size in bytes (set on ACK only) WIDTH uint16 // Width of a matrix or image @@ -8004,7 +7705,6 @@ func (m *DataTransmissionHandshake) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.JPG_QUALITY) } -// // MESSAGE ENCAPSULATED_DATA // // MAVLINK_MSG_ID_ENCAPSULATED_DATA 131 @@ -8012,8 +7712,6 @@ func (m *DataTransmissionHandshake) Decode(buf []byte) { // MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255 // // MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC 223 -// -// type EncapsulatedData struct { SEQNR uint16 // sequence number (starting with 0 on every transmission) DATA [253]uint8 // image data bytes @@ -8061,7 +7759,6 @@ const ( MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_data_LEN = 253 ) -// // MESSAGE DISTANCE_SENSOR // // MAVLINK_MSG_ID_DISTANCE_SENSOR 132 @@ -8069,8 +7766,6 @@ const ( // MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14 // // MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85 -// -// type DistanceSensor struct { TIME_BOOT_MS uint32 // Time since system boot MIN_DISTANCE uint16 // Minimum distance the sensor can measure in centimeters @@ -8138,7 +7833,6 @@ func (m *DistanceSensor) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.COVARIANCE) } -// // MESSAGE TERRAIN_REQUEST // // MAVLINK_MSG_ID_TERRAIN_REQUEST 133 @@ -8146,8 +7840,6 @@ func (m *DistanceSensor) Decode(buf []byte) { // MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN 18 // // MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC 6 -// -// type TerrainRequest struct { MASK uint64 // Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits) LAT int32 // Latitude of SW corner of first grid (degrees *10^7) @@ -8199,7 +7891,6 @@ func (m *TerrainRequest) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.GRID_SPACING) } -// // MESSAGE TERRAIN_DATA // // MAVLINK_MSG_ID_TERRAIN_DATA 134 @@ -8207,8 +7898,6 @@ func (m *TerrainRequest) Decode(buf []byte) { // MAVLINK_MSG_ID_TERRAIN_DATA_LEN 43 // // MAVLINK_MSG_ID_TERRAIN_DATA_CRC 229 -// -// type TerrainData struct { LAT int32 // Latitude of SW corner of first grid (degrees *10^7) LON int32 // Longitude of SW corner of first grid (in degrees *10^7) @@ -8268,7 +7957,6 @@ const ( MAVLINK_MSG_TERRAIN_DATA_FIELD_data_LEN = 16 ) -// // MESSAGE TERRAIN_CHECK // // MAVLINK_MSG_ID_TERRAIN_CHECK 135 @@ -8276,8 +7964,6 @@ const ( // MAVLINK_MSG_ID_TERRAIN_CHECK_LEN 8 // // MAVLINK_MSG_ID_TERRAIN_CHECK_CRC 203 -// -// type TerrainCheck struct { LAT int32 // Latitude (degrees *10^7) LON int32 // Longitude (degrees *10^7) @@ -8321,7 +8007,6 @@ func (m *TerrainCheck) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.LON) } -// // MESSAGE TERRAIN_REPORT // // MAVLINK_MSG_ID_TERRAIN_REPORT 136 @@ -8329,8 +8014,6 @@ func (m *TerrainCheck) Decode(buf []byte) { // MAVLINK_MSG_ID_TERRAIN_REPORT_LEN 22 // // MAVLINK_MSG_ID_TERRAIN_REPORT_CRC 1 -// -// type TerrainReport struct { LAT int32 // Latitude (degrees *10^7) LON int32 // Longitude (degrees *10^7) @@ -8394,7 +8077,6 @@ func (m *TerrainReport) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.LOADED) } -// // MESSAGE BATTERY_STATUS // // MAVLINK_MSG_ID_BATTERY_STATUS 147 @@ -8402,8 +8084,6 @@ func (m *TerrainReport) Decode(buf []byte) { // MAVLINK_MSG_ID_BATTERY_STATUS_LEN 24 // // MAVLINK_MSG_ID_BATTERY_STATUS_CRC 177 -// -// type BatteryStatus struct { CURRENT_CONSUMED int32 // Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate ENERGY_CONSUMED int32 // Consumed energy, in 100*Joules (integrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate @@ -8483,7 +8163,6 @@ func (m *BatteryStatus) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.BATTERY_REMAINING) } -// // MESSAGE SETPOINT_8DOF // // MAVLINK_MSG_ID_SETPOINT_8DOF 148 @@ -8491,8 +8170,6 @@ func (m *BatteryStatus) Decode(buf []byte) { // MAVLINK_MSG_ID_SETPOINT_8DOF_LEN 33 // // MAVLINK_MSG_ID_SETPOINT_8DOF_CRC 241 -// -// type Setpoint8Dof struct { VAL1 float32 // Value 1 VAL2 float32 // Value 2 @@ -8564,7 +8241,6 @@ func (m *Setpoint8Dof) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) } -// // MESSAGE SETPOINT_6DOF // // MAVLINK_MSG_ID_SETPOINT_6DOF 149 @@ -8572,8 +8248,6 @@ func (m *Setpoint8Dof) Decode(buf []byte) { // MAVLINK_MSG_ID_SETPOINT_6DOF_LEN 25 // // MAVLINK_MSG_ID_SETPOINT_6DOF_CRC 15 -// -// type Setpoint6Dof struct { TRANS_X float32 // Translational Component in x TRANS_Y float32 // Translational Component in y @@ -8637,7 +8311,6 @@ func (m *Setpoint6Dof) Decode(buf []byte) { binary.Read(data, binary.LittleEndian, &m.TARGET_SYSTEM) } -// // MESSAGE MEMORY_VECT // // MAVLINK_MSG_ID_MEMORY_VECT 249 @@ -8645,8 +8318,6 @@ func (m *Setpoint6Dof) Decode(buf []byte) { // MAVLINK_MSG_ID_MEMORY_VECT_LEN 36 // // MAVLINK_MSG_ID_MEMORY_VECT_CRC 204 -// -// type MemoryVect struct { ADDRESS uint16 // Starting address of the debug variables VER uint8 // Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below @@ -8702,7 +8373,6 @@ const ( MAVLINK_MSG_MEMORY_VECT_FIELD_value_LEN = 32 ) -// // MESSAGE DEBUG_VECT // // MAVLINK_MSG_ID_DEBUG_VECT 250 @@ -8710,8 +8380,6 @@ const ( // MAVLINK_MSG_ID_DEBUG_VECT_LEN 30 // // MAVLINK_MSG_ID_DEBUG_VECT_CRC 49 -// -// type DebugVect struct { TIME_USEC uint64 // Timestamp X float32 // x @@ -8771,7 +8439,6 @@ const ( MAVLINK_MSG_DEBUG_VECT_FIELD_name_LEN = 10 ) -// // MESSAGE NAMED_VALUE_FLOAT // // MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251 @@ -8779,8 +8446,6 @@ const ( // MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18 // // MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC 170 -// -// type NamedValueFloat struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) VALUE float32 // Floating point value @@ -8832,7 +8497,6 @@ const ( MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_name_LEN = 10 ) -// // MESSAGE NAMED_VALUE_INT // // MAVLINK_MSG_ID_NAMED_VALUE_INT 252 @@ -8840,8 +8504,6 @@ const ( // MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18 // // MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC 44 -// -// type NamedValueInt struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) VALUE int32 // Signed integer value @@ -8893,7 +8555,6 @@ const ( MAVLINK_MSG_NAMED_VALUE_INT_FIELD_name_LEN = 10 ) -// // MESSAGE STATUSTEXT // // MAVLINK_MSG_ID_STATUSTEXT 253 @@ -8901,8 +8562,6 @@ const ( // MAVLINK_MSG_ID_STATUSTEXT_LEN 51 // // MAVLINK_MSG_ID_STATUSTEXT_CRC 83 -// -// type Statustext struct { SEVERITY uint8 // Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. TEXT [50]uint8 // Status text message, without null termination character @@ -8950,7 +8609,6 @@ const ( MAVLINK_MSG_STATUSTEXT_FIELD_text_LEN = 50 ) -// // MESSAGE DEBUG // // MAVLINK_MSG_ID_DEBUG 254 @@ -8958,8 +8616,6 @@ const ( // MAVLINK_MSG_ID_DEBUG_LEN 9 // // MAVLINK_MSG_ID_DEBUG_CRC 46 -// -// type Debug struct { TIME_BOOT_MS uint32 // Timestamp (milliseconds since system boot) VALUE float32 // DEBUG value diff --git a/platforms/mavlink/common/mavlink.go b/platforms/mavlink/common/mavlink.go index dfd961281..b48748713 100644 --- a/platforms/mavlink/common/mavlink.go +++ b/platforms/mavlink/common/mavlink.go @@ -1,3 +1,4 @@ +//nolint:errcheck // to much code to fix it immediately package mavlink // @@ -160,7 +161,6 @@ func read(r io.Reader, length int) ([]byte, error) { return buf, nil } -// // Accumulate the X.25 CRC by adding one char at a time. // // The checksum function adds the hash of one char at a time to the @@ -168,7 +168,6 @@ func read(r io.Reader, length int) ([]byte, error) { // // data to hash // crcAccum the already accumulated checksum -// func crcAccumulate(data uint8, crcAccum uint16) uint16 { /*Accumulate one byte of data into the CRC*/ var tmp uint8 @@ -179,18 +178,14 @@ func crcAccumulate(data uint8, crcAccum uint16) uint16 { return crcAccum } -// // Initiliaze the buffer for the X.25 CRC -// func crcInit() uint16 { return X25_INIT_CRC } -// // Calculates the X.25 checksum on a byte buffer // // return the checksum over the buffer bytes -// func crcCalculate(m *MAVLinkPacket) uint16 { crc := crcInit() diff --git a/platforms/mavlink/mavlink_driver_test.go b/platforms/mavlink/mavlink_driver_test.go index 5e7eca898..4ac9c5cb4 100644 --- a/platforms/mavlink/mavlink_driver_test.go +++ b/platforms/mavlink/mavlink_driver_test.go @@ -46,16 +46,16 @@ func TestMavlinkDriverStart(t *testing.T) { packet := make(chan *common.MAVLinkPacket) message := make(chan common.MAVLinkMessage) - d.On(PacketEvent, func(data interface{}) { + _ = d.On(PacketEvent, func(data interface{}) { packet <- data.(*common.MAVLinkPacket) }) - d.On(MessageEvent, func(data interface{}) { + _ = d.On(MessageEvent, func(data interface{}) { message <- data.(common.MAVLinkMessage) }) - d.On(ErrorIOEvent, func(data interface{}) { + _ = d.On(ErrorIOEvent, func(data interface{}) { err <- data.(error) }) - d.On(ErrorMAVLinkEvent, func(data interface{}) { + _ = d.On(ErrorMAVLinkEvent, func(data interface{}) { err <- data.(error) }) diff --git a/platforms/mavlink/mavlink_udp_adaptor_test.go b/platforms/mavlink/mavlink_udp_adaptor_test.go index 84f47bd7e..5e9f1dd00 100644 --- a/platforms/mavlink/mavlink_udp_adaptor_test.go +++ b/platforms/mavlink/mavlink_udp_adaptor_test.go @@ -71,8 +71,8 @@ func TestMavlinkUDPAdaptorConnectAndFinalize(t *testing.T) { func TestMavlinkUDPAdaptorWrite(t *testing.T) { a := initTestMavlinkUDPAdaptor() - a.Connect() - defer a.Finalize() + _ = a.Connect() + defer func() { _ = a.Finalize() }() m := NewMockUDPConnection() m.TestWriteTo = func([]byte, net.Addr) (int, error) { @@ -87,8 +87,8 @@ func TestMavlinkUDPAdaptorWrite(t *testing.T) { func TestMavlinkReadMAVLinkReadDefaultPacket(t *testing.T) { a := initTestMavlinkUDPAdaptor() - a.Connect() - defer a.Finalize() + _ = a.Connect() + defer func() { _ = a.Finalize() }() m := NewMockUDPConnection() @@ -106,8 +106,8 @@ func TestMavlinkReadMAVLinkReadDefaultPacket(t *testing.T) { func TestMavlinkReadMAVLinkPacketReadError(t *testing.T) { a := initTestMavlinkUDPAdaptor() - a.Connect() - defer a.Finalize() + _ = a.Connect() + defer func() { _ = a.Finalize() }() m := NewMockUDPConnection() diff --git a/platforms/megapi/megapi_adaptor.go b/platforms/megapi/megapi_adaptor.go index f2b6fdaa4..bdbf61063 100644 --- a/platforms/megapi/megapi_adaptor.go +++ b/platforms/megapi/megapi_adaptor.go @@ -61,7 +61,9 @@ func (megaPi *Adaptor) Connect() error { for { select { case bytes := <-megaPi.writeBytesChannel: - megaPi.connection.Write(bytes) + if _, err := megaPi.connection.Write(bytes); err != nil { + panic(err) + } time.Sleep(10 * time.Millisecond) case <-megaPi.finalizeChannel: megaPi.finalizeChannel <- struct{}{} diff --git a/platforms/megapi/motor_driver.go b/platforms/megapi/motor_driver.go index 47d08d7db..1efce6f9a 100644 --- a/platforms/megapi/motor_driver.go +++ b/platforms/megapi/motor_driver.go @@ -45,8 +45,7 @@ func (m *MotorDriver) Start() error { m.syncRoot.Lock() defer m.syncRoot.Unlock() m.halted = false - m.speedHelper(0) - return nil + return m.speedHelper(0) } // Halt terminates the Driver interface @@ -54,8 +53,7 @@ func (m *MotorDriver) Halt() error { m.syncRoot.Lock() defer m.syncRoot.Unlock() m.halted = true - m.speedHelper(0) - return nil + return m.speedHelper(0) } // Connection returns the Connection associated with the Driver @@ -70,25 +68,30 @@ func (m *MotorDriver) Speed(speed int16) error { if m.halted { return nil } - m.speedHelper(speed) - return nil + return m.speedHelper(speed) } // there is some sort of bug on the hardware such that you cannot // send the exact same speed to 2 different motors consecutively // hence we ensure we always alternate speeds -func (m *MotorDriver) speedHelper(speed int16) { - m.sendSpeed(speed - 1) - m.sendSpeed(speed) +func (m *MotorDriver) speedHelper(speed int16) error { + if err := m.sendSpeed(speed - 1); err != nil { + return err + } + return m.sendSpeed(speed) } // sendSpeed sets the motors speed to the specified value -func (m *MotorDriver) sendSpeed(speed int16) { +func (m *MotorDriver) sendSpeed(speed int16) error { bufOut := new(bytes.Buffer) // byte sequence: 0xff, 0x55, id, action, device, port bufOut.Write([]byte{0xff, 0x55, 0x6, 0x0, 0x2, 0xa, m.port}) - binary.Write(bufOut, binary.LittleEndian, speed) + if err := binary.Write(bufOut, binary.LittleEndian, speed); err != nil { + return err + } bufOut.Write([]byte{0xa}) m.megaPi.writeBytesChannel <- bufOut.Bytes() + + return nil } diff --git a/platforms/microbit/accelerometer_driver.go b/platforms/microbit/accelerometer_driver.go index a8da09462..b1cc4e3a9 100644 --- a/platforms/microbit/accelerometer_driver.go +++ b/platforms/microbit/accelerometer_driver.go @@ -29,7 +29,7 @@ type AccelerometerData struct { const ( // BLE services - accelerometerService = "e95d0753251d470aa062fa1922dfa9a8" + //accelerometerService = "e95d0753251d470aa062fa1922dfa9a8" // BLE characteristics accelerometerCharacteristic = "e95dca4b251d470aa062fa1922dfa9a8" @@ -66,15 +66,21 @@ func (b *AccelerometerDriver) adaptor() ble.BLEConnector { } // Start tells driver to get ready to do work -func (b *AccelerometerDriver) Start() (err error) { +func (b *AccelerometerDriver) Start() error { // subscribe to accelerometer notifications - b.adaptor().Subscribe(accelerometerCharacteristic, func(data []byte, e error) { + return b.adaptor().Subscribe(accelerometerCharacteristic, func(data []byte, e error) { a := &RawAccelerometerData{X: 0, Y: 0, Z: 0} buf := bytes.NewBuffer(data) - binary.Read(buf, binary.LittleEndian, &a.X) - binary.Read(buf, binary.LittleEndian, &a.Y) - binary.Read(buf, binary.LittleEndian, &a.Z) + if err := binary.Read(buf, binary.LittleEndian, &a.X); err != nil { + panic(err) + } + if err := binary.Read(buf, binary.LittleEndian, &a.Y); err != nil { + panic(err) + } + if err := binary.Read(buf, binary.LittleEndian, &a.Z); err != nil { + panic(err) + } result := &AccelerometerData{ X: float32(a.X) / 1000.0, @@ -83,11 +89,7 @@ func (b *AccelerometerDriver) Start() (err error) { b.Publish(b.Event(Accelerometer), result) }) - - return } // Halt stops LED driver (void) -func (b *AccelerometerDriver) Halt() (err error) { - return -} +func (b *AccelerometerDriver) Halt() error { return nil } diff --git a/platforms/microbit/accelerometer_driver_test.go b/platforms/microbit/accelerometer_driver_test.go index 36db696e0..7e1786c11 100644 --- a/platforms/microbit/accelerometer_driver_test.go +++ b/platforms/microbit/accelerometer_driver_test.go @@ -33,8 +33,8 @@ func TestAccelerometerDriverReadData(t *testing.T) { sem := make(chan bool) a := NewBleTestAdaptor() d := NewAccelerometerDriver(a) - d.Start() - d.On(Accelerometer, func(data interface{}) { + _ = d.Start() + _ = d.On(Accelerometer, func(data interface{}) { gobottest.Assert(t, data.(*AccelerometerData).X, float32(8.738)) gobottest.Assert(t, data.(*AccelerometerData).Y, float32(8.995)) gobottest.Assert(t, data.(*AccelerometerData).Z, float32(9.252)) diff --git a/platforms/microbit/button_driver.go b/platforms/microbit/button_driver.go index b91c61120..09b17107a 100644 --- a/platforms/microbit/button_driver.go +++ b/platforms/microbit/button_driver.go @@ -14,7 +14,7 @@ type ButtonDriver struct { const ( // BLE services - buttonService = "e95d9882251d470aa062fa1922dfa9a8" + //buttonService = "e95d9882251d470aa062fa1922dfa9a8" // BLE characteristics buttonACharacteristic = "e95dda90251d470aa062fa1922dfa9a8" @@ -56,21 +56,19 @@ func (b *ButtonDriver) adaptor() ble.BLEConnector { } // Start tells driver to get ready to do work -func (b *ButtonDriver) Start() (err error) { +func (b *ButtonDriver) Start() error { // subscribe to button A notifications - b.adaptor().Subscribe(buttonACharacteristic, func(data []byte, e error) { + if err := b.adaptor().Subscribe(buttonACharacteristic, func(data []byte, e error) { b.Publish(b.Event(ButtonA), data) - }) + }); err != nil { + return err + } // subscribe to button B notifications - b.adaptor().Subscribe(buttonBCharacteristic, func(data []byte, e error) { + return b.adaptor().Subscribe(buttonBCharacteristic, func(data []byte, e error) { b.Publish(b.Event(ButtonB), data) }) - - return } // Halt stops LED driver (void) -func (b *ButtonDriver) Halt() (err error) { - return -} +func (b *ButtonDriver) Halt() error { return nil } diff --git a/platforms/microbit/button_driver_test.go b/platforms/microbit/button_driver_test.go index d2a488f6d..007f3881c 100644 --- a/platforms/microbit/button_driver_test.go +++ b/platforms/microbit/button_driver_test.go @@ -33,8 +33,8 @@ func TestButtonDriverReadData(t *testing.T) { sem := make(chan bool) a := NewBleTestAdaptor() d := NewButtonDriver(a) - d.Start() - d.On(ButtonB, func(data interface{}) { + _ = d.Start() + _ = d.On(ButtonB, func(data interface{}) { sem <- true }) diff --git a/platforms/microbit/helpers_test.go b/platforms/microbit/helpers_test.go index e056ebcca..8c94a9615 100644 --- a/platforms/microbit/helpers_test.go +++ b/platforms/microbit/helpers_test.go @@ -40,7 +40,6 @@ func (t *bleTestClientAdaptor) WriteCharacteristic(cUUID string, data []byte) (e return t.testWriteCharacteristic(cUUID, data) } -//nolint:revive // in tests it is be helpful to see the meaning of the parameters by name func (t *bleTestClientAdaptor) Subscribe(cUUID string, f func([]byte, error)) (err error) { t.testSubscribe = f return diff --git a/platforms/microbit/io_pin_driver.go b/platforms/microbit/io_pin_driver.go index 363bac786..b855c16bc 100644 --- a/platforms/microbit/io_pin_driver.go +++ b/platforms/microbit/io_pin_driver.go @@ -22,7 +22,7 @@ type IOPinDriver struct { const ( // BLE services - ioPinService = "e95d127b251d470aa062fa1922dfa9a8" + //ioPinService = "e95d127b251d470aa062fa1922dfa9a8" // BLE characteristics pinDataCharacteristic = "e95d8d00251d470aa062fa1922dfa9a8" @@ -62,19 +62,16 @@ func (b *IOPinDriver) adaptor() ble.BLEConnector { } // Start tells driver to get ready to do work -func (b *IOPinDriver) Start() (err error) { - _, err = b.ReadPinADConfig() - if err != nil { - return +func (b *IOPinDriver) Start() error { + if _, err := b.ReadPinADConfig(); err != nil { + return err } - _, err = b.ReadPinIOConfig() - return + _, err := b.ReadPinIOConfig() + return err } // Halt stops driver (void) -func (b *IOPinDriver) Halt() (err error) { - return -} +func (b *IOPinDriver) Halt() error { return nil } // ReadAllPinData reads and returns the pin data for all pins func (b *IOPinDriver) ReadAllPinData() (pins []PinData) { @@ -93,10 +90,10 @@ func (b *IOPinDriver) ReadAllPinData() (pins []PinData) { } // WritePinData writes the pin data for a single pin -func (b *IOPinDriver) WritePinData(pin string, data byte) (err error) { +func (b *IOPinDriver) WritePinData(pin string, data byte) error { i, err := strconv.Atoi(pin) if err != nil { - return + return err } buf := []byte{byte(i), data} @@ -105,10 +102,10 @@ func (b *IOPinDriver) WritePinData(pin string, data byte) (err error) { } // ReadPinADConfig reads and returns the pin A/D config mask for all pins -func (b *IOPinDriver) ReadPinADConfig() (config int, err error) { - c, e := b.adaptor().ReadCharacteristic(pinADConfigCharacteristic) - if e != nil { - return 0, e +func (b *IOPinDriver) ReadPinADConfig() (int, error) { + c, err := b.adaptor().ReadCharacteristic(pinADConfigCharacteristic) + if err != nil { + return 0, err } var result byte for i := 0; i < 4; i++ { @@ -120,19 +117,21 @@ func (b *IOPinDriver) ReadPinADConfig() (config int, err error) { } // WritePinADConfig writes the pin A/D config mask for all pins -func (b *IOPinDriver) WritePinADConfig(config int) (err error) { +func (b *IOPinDriver) WritePinADConfig(config int) error { b.adMask = config data := &bytes.Buffer{} - binary.Write(data, binary.LittleEndian, uint32(config)) - err = b.adaptor().WriteCharacteristic(pinADConfigCharacteristic, data.Bytes()) - return + if err := binary.Write(data, binary.LittleEndian, uint32(config)); err != nil { + return err + } + + return b.adaptor().WriteCharacteristic(pinADConfigCharacteristic, data.Bytes()) } // ReadPinIOConfig reads and returns the pin IO config mask for all pins -func (b *IOPinDriver) ReadPinIOConfig() (config int, err error) { - c, e := b.adaptor().ReadCharacteristic(pinIOConfigCharacteristic) - if e != nil { - return 0, e +func (b *IOPinDriver) ReadPinIOConfig() (int, error) { + c, err := b.adaptor().ReadCharacteristic(pinIOConfigCharacteristic) + if err != nil { + return 0, err } var result byte @@ -145,77 +144,99 @@ func (b *IOPinDriver) ReadPinIOConfig() (config int, err error) { } // WritePinIOConfig writes the pin I/O config mask for all pins -func (b *IOPinDriver) WritePinIOConfig(config int) (err error) { +func (b *IOPinDriver) WritePinIOConfig(config int) error { b.ioMask = config data := &bytes.Buffer{} - binary.Write(data, binary.LittleEndian, uint32(config)) - err = b.adaptor().WriteCharacteristic(pinIOConfigCharacteristic, data.Bytes()) - return + if err := binary.Write(data, binary.LittleEndian, uint32(config)); err != nil { + return err + } + + return b.adaptor().WriteCharacteristic(pinIOConfigCharacteristic, data.Bytes()) } // DigitalRead reads from a pin -func (b *IOPinDriver) DigitalRead(pin string) (val int, err error) { +func (b *IOPinDriver) DigitalRead(pin string) (int, error) { p, err := validatedPin(pin) if err != nil { - return + return 0, err } - b.ensureDigital(p) - b.ensureInput(p) + if err := b.ensureDigital(p); err != nil { + return 0, err + } + if err := b.ensureInput(p); err != nil { + return 0, err + } pins := b.ReadAllPinData() return int(pins[p].value), nil } // DigitalWrite writes to a pin -func (b *IOPinDriver) DigitalWrite(pin string, level byte) (err error) { +func (b *IOPinDriver) DigitalWrite(pin string, level byte) error { p, err := validatedPin(pin) if err != nil { - return + return err } - b.ensureDigital(p) - b.ensureOutput(p) + if err := b.ensureDigital(p); err != nil { + return err + } + if err := b.ensureOutput(p); err != nil { + return err + } return b.WritePinData(pin, level) } // AnalogRead reads from a pin -func (b *IOPinDriver) AnalogRead(pin string) (val int, err error) { +func (b *IOPinDriver) AnalogRead(pin string) (int, error) { p, err := validatedPin(pin) if err != nil { - return + return 0, err } - b.ensureAnalog(p) - b.ensureInput(p) + if err := b.ensureAnalog(p); err != nil { + return 0, err + } + if err := b.ensureInput(p); err != nil { + return 0, err + } pins := b.ReadAllPinData() return int(pins[p].value), nil } -func (b *IOPinDriver) ensureDigital(pin int) { +func (b *IOPinDriver) ensureDigital(pin int) error { if hasBit(b.adMask, pin) { - b.WritePinADConfig(clearBit(b.adMask, pin)) + return b.WritePinADConfig(clearBit(b.adMask, pin)) } + + return nil } -func (b *IOPinDriver) ensureAnalog(pin int) { +func (b *IOPinDriver) ensureAnalog(pin int) error { if !hasBit(b.adMask, pin) { - b.WritePinADConfig(setBit(b.adMask, pin)) + return b.WritePinADConfig(setBit(b.adMask, pin)) } + + return nil } -func (b *IOPinDriver) ensureInput(pin int) { +func (b *IOPinDriver) ensureInput(pin int) error { if !hasBit(b.ioMask, pin) { - b.WritePinIOConfig(setBit(b.ioMask, pin)) + return b.WritePinIOConfig(setBit(b.ioMask, pin)) } + + return nil } -func (b *IOPinDriver) ensureOutput(pin int) { +func (b *IOPinDriver) ensureOutput(pin int) error { if hasBit(b.ioMask, pin) { - b.WritePinIOConfig(clearBit(b.ioMask, pin)) + return b.WritePinIOConfig(clearBit(b.ioMask, pin)) } + + return nil } func validatedPin(pin string) (int, error) { diff --git a/platforms/microbit/led_driver.go b/platforms/microbit/led_driver.go index 877a5441e..3c9af03de 100644 --- a/platforms/microbit/led_driver.go +++ b/platforms/microbit/led_driver.go @@ -14,7 +14,7 @@ type LEDDriver struct { const ( // BLE services - ledService = "e95dd91d251d470aa062fa1922dfa9a8" + //ledService = "e95dd91d251d470aa062fa1922dfa9a8" // BLE characteristics ledMatrixStateCharacteristic = "e95d7b77251d470aa062fa1922dfa9a8" diff --git a/platforms/microbit/led_driver_test.go b/platforms/microbit/led_driver_test.go index 7e02da79f..9d4003c20 100644 --- a/platforms/microbit/led_driver_test.go +++ b/platforms/microbit/led_driver_test.go @@ -30,19 +30,19 @@ func TestLEDDriverStartAndHalt(t *testing.T) { func TestLEDDriverWriteMatrix(t *testing.T) { d := initTestLEDDriver() - d.Start() + _ = d.Start() gobottest.Assert(t, d.WriteMatrix([]byte{0x01, 0x02}), nil) } func TestLEDDriverWriteText(t *testing.T) { d := initTestLEDDriver() - d.Start() + _ = d.Start() gobottest.Assert(t, d.WriteText("Hello"), nil) } func TestLEDDriverCommands(t *testing.T) { d := initTestLEDDriver() - d.Start() + _ = d.Start() gobottest.Assert(t, d.Blank(), nil) gobottest.Assert(t, d.Solid(), nil) gobottest.Assert(t, d.UpRightArrow(), nil) diff --git a/platforms/microbit/magnetometer_driver.go b/platforms/microbit/magnetometer_driver.go index 148ceb5b2..c899be683 100644 --- a/platforms/microbit/magnetometer_driver.go +++ b/platforms/microbit/magnetometer_driver.go @@ -29,7 +29,7 @@ type MagnetometerData struct { const ( // BLE services - magnetometerService = "e95df2d8251d470aa062fa1922dfa9a8" + //magnetometerService = "e95df2d8251d470aa062fa1922dfa9a8" // BLE characteristics magnetometerCharacteristic = "e95dfb11251d470aa062fa1922dfa9a8" @@ -66,15 +66,21 @@ func (b *MagnetometerDriver) adaptor() ble.BLEConnector { } // Start tells driver to get ready to do work -func (b *MagnetometerDriver) Start() (err error) { +func (b *MagnetometerDriver) Start() error { // subscribe to magnetometer notifications - b.adaptor().Subscribe(magnetometerCharacteristic, func(data []byte, e error) { + return b.adaptor().Subscribe(magnetometerCharacteristic, func(data []byte, e error) { a := &RawMagnetometerData{X: 0, Y: 0, Z: 0} buf := bytes.NewBuffer(data) - binary.Read(buf, binary.LittleEndian, &a.X) - binary.Read(buf, binary.LittleEndian, &a.Y) - binary.Read(buf, binary.LittleEndian, &a.Z) + if err := binary.Read(buf, binary.LittleEndian, &a.X); err != nil { + panic(err) + } + if err := binary.Read(buf, binary.LittleEndian, &a.Y); err != nil { + panic(err) + } + if err := binary.Read(buf, binary.LittleEndian, &a.Z); err != nil { + panic(err) + } result := &MagnetometerData{ X: float32(a.X) / 1000.0, @@ -83,11 +89,7 @@ func (b *MagnetometerDriver) Start() (err error) { b.Publish(b.Event(Magnetometer), result) }) - - return } // Halt stops LED driver (void) -func (b *MagnetometerDriver) Halt() (err error) { - return -} +func (b *MagnetometerDriver) Halt() error { return nil } diff --git a/platforms/microbit/magnetometer_driver_test.go b/platforms/microbit/magnetometer_driver_test.go index 8e5c59c98..03ef4145f 100644 --- a/platforms/microbit/magnetometer_driver_test.go +++ b/platforms/microbit/magnetometer_driver_test.go @@ -33,8 +33,8 @@ func TestMagnetometerDriverReadData(t *testing.T) { sem := make(chan bool) a := NewBleTestAdaptor() d := NewMagnetometerDriver(a) - d.Start() - d.On(Magnetometer, func(data interface{}) { + _ = d.Start() + _ = d.On(Magnetometer, func(data interface{}) { gobottest.Assert(t, data.(*MagnetometerData).X, float32(8.738)) gobottest.Assert(t, data.(*MagnetometerData).Y, float32(8.995)) gobottest.Assert(t, data.(*MagnetometerData).Z, float32(9.252)) diff --git a/platforms/microbit/temperature_driver.go b/platforms/microbit/temperature_driver.go index c14420493..0e7ca7ea1 100644 --- a/platforms/microbit/temperature_driver.go +++ b/platforms/microbit/temperature_driver.go @@ -16,7 +16,7 @@ type TemperatureDriver struct { const ( // BLE services - temperatureService = "e95d6100251d470aa062fa1922dfa9a8" + //temperatureService = "e95d6100251d470aa062fa1922dfa9a8" // BLE characteristics temperatureCharacteristic = "e95d9250251d470aa062fa1922dfa9a8" @@ -53,9 +53,9 @@ func (b *TemperatureDriver) adaptor() ble.BLEConnector { } // Start tells driver to get ready to do work -func (b *TemperatureDriver) Start() (err error) { +func (b *TemperatureDriver) Start() error { // subscribe to temperature notifications - b.adaptor().Subscribe(temperatureCharacteristic, func(data []byte, e error) { + return b.adaptor().Subscribe(temperatureCharacteristic, func(data []byte, e error) { var l int8 buf := bytes.NewBuffer(data) val, _ := buf.ReadByte() @@ -63,11 +63,7 @@ func (b *TemperatureDriver) Start() (err error) { b.Publish(b.Event(Temperature), l) }) - - return } // Halt stops Temperature driver (void) -func (b *TemperatureDriver) Halt() (err error) { - return -} +func (b *TemperatureDriver) Halt() error { return nil } diff --git a/platforms/microbit/temperature_driver_test.go b/platforms/microbit/temperature_driver_test.go index 6bd40ca4e..8abeef661 100644 --- a/platforms/microbit/temperature_driver_test.go +++ b/platforms/microbit/temperature_driver_test.go @@ -33,8 +33,8 @@ func TestTemperatureDriverReadData(t *testing.T) { sem := make(chan bool) a := NewBleTestAdaptor() d := NewTemperatureDriver(a) - d.Start() - d.On(Temperature, func(data interface{}) { + _ = d.Start() + _ = d.On(Temperature, func(data interface{}) { gobottest.Assert(t, data, int8(0x22)) sem <- true }) diff --git a/platforms/mqtt/mqtt_adaptor.go b/platforms/mqtt/mqtt_adaptor.go index 9268f2b98..d70badb05 100644 --- a/platforms/mqtt/mqtt_adaptor.go +++ b/platforms/mqtt/mqtt_adaptor.go @@ -8,7 +8,6 @@ import ( "gobot.io/x/gobot/v2" paho "github.com/eclipse/paho.mqtt.golang" - multierror "github.com/hashicorp/go-multierror" "github.com/pkg/errors" ) @@ -112,27 +111,26 @@ func (a *Adaptor) ClientKey() string { return a.clientKey } func (a *Adaptor) SetClientKey(val string) { a.clientKey = val } // Connect returns true if connection to mqtt is established -func (a *Adaptor) Connect() (err error) { +func (a *Adaptor) Connect() error { a.client = paho.NewClient(a.createClientOptions()) if token := a.client.Connect(); token.Wait() && token.Error() != nil { - err = multierror.Append(err, token.Error()) + return token.Error() } - return + return nil } // Disconnect returns true if connection to mqtt is closed -func (a *Adaptor) Disconnect() (err error) { +func (a *Adaptor) Disconnect() error { if a.client != nil { a.client.Disconnect(500) } - return + return nil } // Finalize returns true if connection to mqtt is finalized successfully -func (a *Adaptor) Finalize() (err error) { - a.Disconnect() - return +func (a *Adaptor) Finalize() error { + return a.Disconnect() } // Publish a message under a specific topic diff --git a/platforms/mqtt/mqtt_adaptor_test.go b/platforms/mqtt/mqtt_adaptor_test.go index 638ad0bdc..db27ec67e 100644 --- a/platforms/mqtt/mqtt_adaptor_test.go +++ b/platforms/mqtt/mqtt_adaptor_test.go @@ -6,7 +6,6 @@ import ( "strings" "testing" - multierror "github.com/hashicorp/go-multierror" "gobot.io/x/gobot/v2" "gobot.io/x/gobot/v2/gobottest" ) @@ -87,10 +86,7 @@ func TestMqttAdaptorConnectSSLError(t *testing.T) { func TestMqttAdaptorConnectWithAuthError(t *testing.T) { a := NewAdaptorWithAuth("xyz://localhost:1883", "client", "user", "pass") - var expected error - expected = multierror.Append(expected, errors.New("network Error : unknown protocol")) - - gobottest.Assert(t, a.Connect(), expected) + gobottest.Assert(t, a.Connect(), errors.New("network Error : unknown protocol")) } func TestMqttAdaptorFinalize(t *testing.T) { @@ -106,7 +102,7 @@ func TestMqttAdaptorCannotPublishUnlessConnected(t *testing.T) { func TestMqttAdaptorPublishWhenConnected(t *testing.T) { a := initTestMqttAdaptor() - a.Connect() + _ = a.Connect() data := []byte("o") gobottest.Assert(t, a.Publish("test", data), true) } @@ -120,7 +116,7 @@ func TestMqttAdaptorCannotOnUnlessConnected(t *testing.T) { func TestMqttAdaptorOnWhenConnected(t *testing.T) { a := initTestMqttAdaptor() - a.Connect() + _ = a.Connect() gobottest.Assert(t, a.On("hola", func(msg Message) { fmt.Println("hola") }), true) diff --git a/platforms/mqtt/mqtt_driver_test.go b/platforms/mqtt/mqtt_driver_test.go index 8f8fb778d..028838db7 100644 --- a/platforms/mqtt/mqtt_driver_test.go +++ b/platforms/mqtt/mqtt_driver_test.go @@ -37,16 +37,16 @@ func TestMqttDriverTopic(t *testing.T) { func TestMqttDriverPublish(t *testing.T) { a := initTestMqttAdaptor() d := NewDriver(a, "/test/topic") - a.Connect() - d.Start() - defer d.Halt() + _ = a.Connect() + _ = d.Start() + defer func() { _ = d.Halt() }() gobottest.Assert(t, d.Publish([]byte{0x01, 0x02, 0x03}), true) } func TestMqttDriverPublishError(t *testing.T) { a := initTestMqttAdaptor() d := NewDriver(a, "/test/topic") - d.Start() - defer d.Halt() + _ = d.Start() + defer func() { _ = d.Halt() }() gobottest.Assert(t, d.Publish([]byte{0x01, 0x02, 0x03}), false) } diff --git a/platforms/nanopi/nanopi_adaptor.go b/platforms/nanopi/nanopi_adaptor.go index 65f244c97..46b67c85d 100644 --- a/platforms/nanopi/nanopi_adaptor.go +++ b/platforms/nanopi/nanopi_adaptor.go @@ -11,8 +11,6 @@ import ( ) const ( - debug = false - pwmInvertedIdentifier = "inversed" defaultI2cBusNumber = 0 diff --git a/platforms/nanopi/nanopi_adaptor_test.go b/platforms/nanopi/nanopi_adaptor_test.go index e506ef67c..e6681c047 100644 --- a/platforms/nanopi/nanopi_adaptor_test.go +++ b/platforms/nanopi/nanopi_adaptor_test.go @@ -83,7 +83,7 @@ func TestDigitalIO(t *testing.T) { // only basic tests needed, further tests are done in "digitalpinsadaptor.go" a, fs := initTestAdaptorWithMockedFilesystem(gpioMockPaths) - a.DigitalWrite("7", 1) + _ = a.DigitalWrite("7", 1) gobottest.Assert(t, fs.Files[gpio203Path+"value"].Contents, "1") fs.Files[gpio199Path+"value"].Contents = "1" diff --git a/platforms/nats/nats_adaptor.go b/platforms/nats/nats_adaptor.go index 5099ef9a2..122cdad9e 100644 --- a/platforms/nats/nats_adaptor.go +++ b/platforms/nats/nats_adaptor.go @@ -1,6 +1,7 @@ package nats import ( + "log" "net/url" "strings" @@ -86,23 +87,23 @@ func (a *Adaptor) Name() string { return a.name } func (a *Adaptor) SetName(n string) { a.name = n } // Connect makes a connection to the Nats server. -func (a *Adaptor) Connect() (err error) { +func (a *Adaptor) Connect() error { + var err error a.client, err = a.connect() - return + return err } // Disconnect from the nats server. -func (a *Adaptor) Disconnect() (err error) { +func (a *Adaptor) Disconnect() error { if a.client != nil { a.client.Close() } - return + return nil } // Finalize is simply a helper method for the disconnect. -func (a *Adaptor) Finalize() (err error) { - a.Disconnect() - return +func (a *Adaptor) Finalize() error { + return a.Disconnect() } // Publish sends a message with the particular topic to the nats server. @@ -110,7 +111,12 @@ func (a *Adaptor) Publish(topic string, message []byte) bool { if a.client == nil { return false } - a.client.Publish(topic, message) + + if err := a.client.Publish(topic, message); err != nil { + log.Println(err) + return false + } + return true } @@ -120,9 +126,12 @@ func (a *Adaptor) On(event string, f func(msg Message)) bool { if a.client == nil { return false } - a.client.Subscribe(event, func(msg *nats.Msg) { + if _, err := a.client.Subscribe(event, func(msg *nats.Msg) { f(msg) - }) + }); err != nil { + log.Println(err) + return false + } return true } diff --git a/platforms/nats/nats_adaptor_test.go b/platforms/nats/nats_adaptor_test.go index f0ff1d49e..469ec6f2b 100644 --- a/platforms/nats/nats_adaptor_test.go +++ b/platforms/nats/nats_adaptor_test.go @@ -72,7 +72,7 @@ func TestNatsAdaptorWithAuth(t *testing.T) { func TestNatsAdapterSetsRootCAs(t *testing.T) { a := initTestNatsAdaptorTLS(nats.RootCAs("test_certs/catest.pem")) gobottest.Assert(t, a.Host, "tls://localhost:4242") - a.Connect() + _ = a.Connect() o := a.client.Opts casPool, err := o.RootCAsCB() gobottest.Assert(t, err, nil) @@ -83,7 +83,7 @@ func TestNatsAdapterSetsRootCAs(t *testing.T) { func TestNatsAdapterSetsClientCerts(t *testing.T) { a := initTestNatsAdaptorTLS(nats.ClientCert("test_certs/client-cert.pem", "test_certs/client-key.pem")) gobottest.Assert(t, a.Host, "tls://localhost:4242") - a.Connect() + _ = a.Connect() cert, err := a.client.Opts.TLSCertCB() gobottest.Assert(t, err, nil) gobottest.Refute(t, cert, nil) @@ -94,7 +94,7 @@ func TestNatsAdapterSetsClientCerts(t *testing.T) { func TestNatsAdapterSetsClientCertsWithUserInfo(t *testing.T) { a := initTestNatsAdaptorTLS(nats.ClientCert("test_certs/client-cert.pem", "test_certs/client-key.pem"), nats.UserInfo("test", "testwd")) gobottest.Assert(t, a.Host, "tls://localhost:4242") - a.Connect() + _ = a.Connect() cert, err := a.client.Opts.TLSCertCB() gobottest.Assert(t, err, nil) gobottest.Refute(t, cert, nil) @@ -108,7 +108,7 @@ func TestNatsAdapterSetsClientCertsWithUserInfo(t *testing.T) { func TestNatsAdaptorPublishWhenConnected(t *testing.T) { t.Skip("TODO: implement this test without requiring actual server connection") a := initTestNatsAdaptor() - a.Connect() + _ = a.Connect() data := []byte("o") gobottest.Assert(t, a.Publish("test", data), true) } @@ -117,7 +117,7 @@ func TestNatsAdaptorPublishWhenConnected(t *testing.T) { func TestNatsAdaptorOnWhenConnected(t *testing.T) { t.Skip("TODO: implement this test without requiring actual server connection") a := initTestNatsAdaptor() - a.Connect() + _ = a.Connect() gobottest.Assert(t, a.On("hola", func(msg Message) { fmt.Println("hola") }), true) @@ -127,7 +127,7 @@ func TestNatsAdaptorOnWhenConnected(t *testing.T) { func TestNatsAdaptorPublishWhenConnectedWithAuth(t *testing.T) { t.Skip("TODO: implement this test without requiring actual server connection") a := NewAdaptorWithAuth("localhost:4222", 49999, "test", "testwd") - a.Connect() + _ = a.Connect() data := []byte("o") gobottest.Assert(t, a.Publish("test", data), true) } @@ -137,7 +137,7 @@ func TestNatsAdaptorOnWhenConnectedWithAuth(t *testing.T) { t.Skip("TODO: implement this test without requiring actual server connection") log.Println("###not skipped###") a := NewAdaptorWithAuth("localhost:4222", 59999, "test", "testwd") - a.Connect() + _ = a.Connect() gobottest.Assert(t, a.On("hola", func(msg Message) { fmt.Println("hola") }), true) diff --git a/platforms/neurosky/neurosky_adaptor_test.go b/platforms/neurosky/neurosky_adaptor_test.go index fe1d8aa17..74237ec7a 100644 --- a/platforms/neurosky/neurosky_adaptor_test.go +++ b/platforms/neurosky/neurosky_adaptor_test.go @@ -19,12 +19,6 @@ type NullReadWriteCloser struct { closeError error } -// func NewNullReadWriteCloser() *NullReadWriteCloser { -// return NullReadWriteCloser{ -// -// } -// } - func (n *NullReadWriteCloser) ReadError(e error) { n.mtx.Lock() defer n.mtx.Unlock() @@ -89,10 +83,10 @@ func TestNeuroskyAdaptorFinalize(t *testing.T) { a.connect = func(n *Adaptor) (io.ReadWriteCloser, error) { return rwc, nil } - a.Connect() + _ = a.Connect() gobottest.Assert(t, a.Finalize(), nil) rwc.CloseError(errors.New("close error")) - a.Connect() + _ = a.Connect() gobottest.Assert(t, a.Finalize(), errors.New("close error")) } diff --git a/platforms/neurosky/neurosky_driver.go b/platforms/neurosky/neurosky_driver.go index f08403ec8..a09328ea5 100644 --- a/platforms/neurosky/neurosky_driver.go +++ b/platforms/neurosky/neurosky_driver.go @@ -120,7 +120,7 @@ func (n *Driver) adaptor() *Adaptor { // Start creates a go routine to listen from serial port // and parse buffer readings -func (n *Driver) Start() (err error) { +func (n *Driver) Start() error { go func() { for { buff := make([]byte, 1024) @@ -128,34 +128,42 @@ func (n *Driver) Start() (err error) { if err != nil { n.Publish(n.Event("error"), err) } else { - n.parse(bytes.NewBuffer(buff)) + if err := n.parse(bytes.NewBuffer(buff)); err != nil { + panic(err) + } } } }() - return + return nil } // Halt stops neurosky driver (void) -func (n *Driver) Halt() (err error) { return } +func (n *Driver) Halt() error { return nil } // parse converts bytes buffer into packets until no more data is present -func (n *Driver) parse(buf *bytes.Buffer) { +func (n *Driver) parse(buf *bytes.Buffer) error { for buf.Len() > 2 { b1, _ := buf.ReadByte() b2, _ := buf.ReadByte() if b1 == BTSync && b2 == BTSync { length, _ := buf.ReadByte() payload := make([]byte, length) - buf.Read(payload) + if _, err := buf.Read(payload); err != nil { + return err + } //checksum, _ := buf.ReadByte() buf.Next(1) - n.parsePacket(bytes.NewBuffer(payload)) + if err := n.parsePacket(bytes.NewBuffer(payload)); err != nil { + panic(err) + } } } + + return nil } // parsePacket publishes event according to data parsed -func (n *Driver) parsePacket(buf *bytes.Buffer) { +func (n *Driver) parsePacket(buf *bytes.Buffer) error { for buf.Len() > 0 { b, _ := buf.ReadByte() switch b { @@ -176,7 +184,9 @@ func (n *Driver) parsePacket(buf *bytes.Buffer) { case CodeWave: buf.Next(1) var ret = make([]byte, 2) - buf.Read(ret) + if _, err := buf.Read(ret); err != nil { + return err + } n.Publish(n.Event("wave"), int16(ret[0])<<8|int16(ret[1])) case CodeAsicEEG: ret := make([]byte, 25) @@ -186,6 +196,8 @@ func (n *Driver) parsePacket(buf *bytes.Buffer) { } } } + + return nil } // parseEEG returns data converted into EEG map diff --git a/platforms/neurosky/neurosky_driver_test.go b/platforms/neurosky/neurosky_driver_test.go index ab73215b1..9f83f5387 100644 --- a/platforms/neurosky/neurosky_driver_test.go +++ b/platforms/neurosky/neurosky_driver_test.go @@ -19,7 +19,7 @@ func initTestNeuroskyDriver() *Driver { a.connect = func(n *Adaptor) (io.ReadWriteCloser, error) { return &NullReadWriteCloser{}, nil } - a.Connect() + _ = a.Connect() return NewDriver(a) } @@ -43,11 +43,11 @@ func TestNeuroskyDriverStart(t *testing.T) { a.connect = func(n *Adaptor) (io.ReadWriteCloser, error) { return rwc, nil } - a.Connect() + _ = a.Connect() d := NewDriver(a) e := errors.New("read error") - d.Once(d.Event(Error), func(data interface{}) { + _ = d.Once(d.Event(Error), func(data interface{}) { gobottest.Assert(t, data.(error), e) sem <- true }) @@ -79,10 +79,10 @@ func TestNeuroskyDriverParse(t *testing.T) { // CodeEx go func() { time.Sleep(5 * time.Millisecond) - d.parse(bytes.NewBuffer([]byte{0xAA, 0xAA, 1, 0x55, 0x00})) + _ = d.parse(bytes.NewBuffer([]byte{0xAA, 0xAA, 1, 0x55, 0x00})) }() - d.On(d.Event(Extended), func(data interface{}) { + _ = d.On(d.Event(Extended), func(data interface{}) { sem <- true }) @@ -95,10 +95,10 @@ func TestNeuroskyDriverParse(t *testing.T) { // CodeSignalQuality go func() { time.Sleep(5 * time.Millisecond) - d.parse(bytes.NewBuffer([]byte{0xAA, 0xAA, 2, 0x02, 100, 0x00})) + _ = d.parse(bytes.NewBuffer([]byte{0xAA, 0xAA, 2, 0x02, 100, 0x00})) }() - d.On(d.Event(Signal), func(data interface{}) { + _ = d.On(d.Event(Signal), func(data interface{}) { gobottest.Assert(t, data.(byte), byte(100)) sem <- true }) @@ -108,10 +108,10 @@ func TestNeuroskyDriverParse(t *testing.T) { // CodeAttention go func() { time.Sleep(5 * time.Millisecond) - d.parse(bytes.NewBuffer([]byte{0xAA, 0xAA, 2, 0x04, 40, 0x00})) + _ = d.parse(bytes.NewBuffer([]byte{0xAA, 0xAA, 2, 0x04, 40, 0x00})) }() - d.On(d.Event(Attention), func(data interface{}) { + _ = d.On(d.Event(Attention), func(data interface{}) { gobottest.Assert(t, data.(byte), byte(40)) sem <- true }) @@ -121,10 +121,10 @@ func TestNeuroskyDriverParse(t *testing.T) { // CodeMeditation go func() { time.Sleep(5 * time.Millisecond) - d.parse(bytes.NewBuffer([]byte{0xAA, 0xAA, 2, 0x05, 60, 0x00})) + _ = d.parse(bytes.NewBuffer([]byte{0xAA, 0xAA, 2, 0x05, 60, 0x00})) }() - d.On(d.Event(Meditation), func(data interface{}) { + _ = d.On(d.Event(Meditation), func(data interface{}) { gobottest.Assert(t, data.(byte), byte(60)) sem <- true }) @@ -134,10 +134,10 @@ func TestNeuroskyDriverParse(t *testing.T) { // CodeBlink go func() { time.Sleep(5 * time.Millisecond) - d.parse(bytes.NewBuffer([]byte{0xAA, 0xAA, 2, 0x16, 150, 0x00})) + _ = d.parse(bytes.NewBuffer([]byte{0xAA, 0xAA, 2, 0x16, 150, 0x00})) }() - d.On(d.Event(Blink), func(data interface{}) { + _ = d.On(d.Event(Blink), func(data interface{}) { gobottest.Assert(t, data.(byte), byte(150)) sem <- true }) @@ -147,10 +147,10 @@ func TestNeuroskyDriverParse(t *testing.T) { // CodeWave go func() { time.Sleep(5 * time.Millisecond) - d.parse(bytes.NewBuffer([]byte{0xAA, 0xAA, 4, 0x80, 0x00, 0x40, 0x11, 0x00})) + _ = d.parse(bytes.NewBuffer([]byte{0xAA, 0xAA, 4, 0x80, 0x00, 0x40, 0x11, 0x00})) }() - d.On(d.Event(Wave), func(data interface{}) { + _ = d.On(d.Event(Wave), func(data interface{}) { gobottest.Assert(t, data.(int16), int16(16401)) sem <- true }) @@ -160,12 +160,12 @@ func TestNeuroskyDriverParse(t *testing.T) { // CodeAsicEEG go func() { time.Sleep(5 * time.Millisecond) - d.parse(bytes.NewBuffer([]byte{0xAA, 0xAA, 30, 0x83, 24, 1, 121, 89, 0, + _ = d.parse(bytes.NewBuffer([]byte{0xAA, 0xAA, 30, 0x83, 24, 1, 121, 89, 0, 97, 26, 0, 30, 189, 0, 57, 1, 0, 62, 160, 0, 31, 127, 0, 18, 207, 0, 13, 108, 0x00})) }() - d.On(d.Event(EEG), func(data interface{}) { + _ = d.On(d.Event(EEG), func(data interface{}) { gobottest.Assert(t, data.(EEGData), EEGData{ diff --git a/platforms/parrot/ardrone/ardrone_driver_test.go b/platforms/parrot/ardrone/ardrone_driver_test.go index ec1bf9c91..dfdf6e26c 100644 --- a/platforms/parrot/ardrone/ardrone_driver_test.go +++ b/platforms/parrot/ardrone/ardrone_driver_test.go @@ -16,7 +16,7 @@ func initTestArdroneDriver() *Driver { } d := NewDriver(a) d.SetName("mydrone") - a.Connect() + _ = a.Connect() return d } diff --git a/platforms/parrot/bebop/bebop_adaptor.go b/platforms/parrot/bebop/bebop_adaptor.go index 23716e1cd..b094b8803 100644 --- a/platforms/parrot/bebop/bebop_adaptor.go +++ b/platforms/parrot/bebop/bebop_adaptor.go @@ -53,10 +53,9 @@ func (a *Adaptor) Name() string { return a.name } func (a *Adaptor) SetName(n string) { a.name = n } // Connect establishes a connection to the ardrone -func (a *Adaptor) Connect() (err error) { - err = a.connect(a) - return +func (a *Adaptor) Connect() error { + return a.connect(a) } // Finalize terminates the connection to the ardrone -func (a *Adaptor) Finalize() (err error) { return } +func (a *Adaptor) Finalize() error { return nil } diff --git a/platforms/parrot/bebop/bebop_adaptor_test.go b/platforms/parrot/bebop/bebop_adaptor_test.go index 65d818bbf..7faf839ca 100644 --- a/platforms/parrot/bebop/bebop_adaptor_test.go +++ b/platforms/parrot/bebop/bebop_adaptor_test.go @@ -39,6 +39,6 @@ func TestBebopAdaptorConnect(t *testing.T) { func TestBebopAdaptorFinalize(t *testing.T) { a := initTestBebopAdaptor() - a.Connect() + _ = a.Connect() gobottest.Assert(t, a.Finalize(), nil) } diff --git a/platforms/parrot/bebop/bebop_driver.go b/platforms/parrot/bebop/bebop_driver.go index 43d685123..b0d1c0f4f 100644 --- a/platforms/parrot/bebop/bebop_driver.go +++ b/platforms/parrot/bebop/bebop_driver.go @@ -57,63 +57,63 @@ func (a *Driver) TakeOff() { } // Land causes the drone to land -func (a *Driver) Land() { - a.adaptor().drone.Land() +func (a *Driver) Land() error { + return a.adaptor().drone.Land() } // Up makes the drone gain altitude. // speed can be a value from `0` to `100`. -func (a *Driver) Up(speed int) { - a.adaptor().drone.Up(speed) +func (a *Driver) Up(speed int) error { + return a.adaptor().drone.Up(speed) } // Down makes the drone reduce altitude. // speed can be a value from `0` to `100`. -func (a *Driver) Down(speed int) { - a.adaptor().drone.Down(speed) +func (a *Driver) Down(speed int) error { + return a.adaptor().drone.Down(speed) } // Left causes the drone to bank to the left, controls the roll, which is // a horizontal movement using the camera as a reference point. // speed can be a value from `0` to `100`. -func (a *Driver) Left(speed int) { - a.adaptor().drone.Left(speed) +func (a *Driver) Left(speed int) error { + return a.adaptor().drone.Left(speed) } // Right causes the drone to bank to the right, controls the roll, which is // a horizontal movement using the camera as a reference point. // speed can be a value from `0` to `100`. -func (a *Driver) Right(speed int) { - a.adaptor().drone.Right(speed) +func (a *Driver) Right(speed int) error { + return a.adaptor().drone.Right(speed) } // Forward causes the drone go forward, controls the pitch. // speed can be a value from `0` to `100`. -func (a *Driver) Forward(speed int) { - a.adaptor().drone.Forward(speed) +func (a *Driver) Forward(speed int) error { + return a.adaptor().drone.Forward(speed) } // Backward causes the drone go forward, controls the pitch. // speed can be a value from `0` to `100`. -func (a *Driver) Backward(speed int) { - a.adaptor().drone.Backward(speed) +func (a *Driver) Backward(speed int) error { + return a.adaptor().drone.Backward(speed) } // Clockwise causes the drone to spin in clockwise direction // speed can be a value from `0` to `100`. -func (a *Driver) Clockwise(speed int) { - a.adaptor().drone.Clockwise(speed) +func (a *Driver) Clockwise(speed int) error { + return a.adaptor().drone.Clockwise(speed) } // CounterClockwise the drone to spin in counter clockwise direction // speed can be a value from `0` to `100`. -func (a *Driver) CounterClockwise(speed int) { - a.adaptor().drone.CounterClockwise(speed) +func (a *Driver) CounterClockwise(speed int) error { + return a.adaptor().drone.CounterClockwise(speed) } // Stop makes the drone to hover in place. -func (a *Driver) Stop() { - a.adaptor().drone.Stop() +func (a *Driver) Stop() error { + return a.adaptor().drone.Stop() } // Video returns a channel which raw video frames will be broadcast on diff --git a/platforms/parrot/bebop/client/client.go b/platforms/parrot/bebop/client/client.go index 91acfa44d..50c76bcbf 100644 --- a/platforms/parrot/bebop/client/client.go +++ b/platforms/parrot/bebop/client/client.go @@ -69,7 +69,9 @@ func NewARStreamFrame(buf []byte) ARStreamFrame { } var number uint16 - binary.Read(bytes.NewReader(buf[0:2]), binary.LittleEndian, &number) + if err := binary.Read(bytes.NewReader(buf[0:2]), binary.LittleEndian, &number); err != nil { + panic(err) + } frame.FrameNumber = int(number) @@ -95,7 +97,9 @@ func NewNetworkFrame(buf []byte) NetworkFrame { } var size uint32 - binary.Read(bytes.NewReader(buf[3:7]), binary.LittleEndian, &size) + if err := binary.Read(bytes.NewReader(buf[3:7]), binary.LittleEndian, &size); err != nil { + panic(err) + } frame.Size = int(size) frame.Data = buf[7:frame.Size] @@ -136,7 +140,9 @@ func networkFrameGenerator() func(*bytes.Buffer, byte, byte) *bytes.Buffer { ret.WriteByte(seq[id]) size := &bytes.Buffer{} - binary.Write(size, binary.LittleEndian, uint32(cmd.Len()+hlen)) + if err := binary.Write(size, binary.LittleEndian, uint32(cmd.Len()+hlen)); err != nil { + panic(err) + } ret.Write(size.Bytes()) ret.Write(cmd.Bytes()) @@ -203,18 +209,16 @@ func (b *Bebop) write(buf []byte) (int, error) { func (b *Bebop) Discover() error { addr, err := net.ResolveTCPAddr("tcp", fmt.Sprintf("%s:%d", b.IP, b.DiscoveryPort)) - if err != nil { return err } b.discoveryClient, err = net.DialTCP("tcp", nil, addr) - if err != nil { return err } - b.discoveryClient.Write( + if _, err := b.discoveryClient.Write( []byte( fmt.Sprintf(`{ "controller_type": "computer", @@ -227,7 +231,9 @@ func (b *Bebop) Discover() error { b.RTPStreamPort, b.RTPControlPort), ), - ) + ); err != nil { + return err + } data := make([]byte, 10240) @@ -325,7 +331,9 @@ func (b *Bebop) FlatTrim() error { cmd.WriteByte(ARCOMMANDS_ID_ARDRONE3_CLASS_PILOTING) tmp := &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, uint16(ARCOMMANDS_ID_ARDRONE3_PILOTING_CMD_FLATTRIM)) + if err := binary.Write(tmp, binary.LittleEndian, uint16(ARCOMMANDS_ID_ARDRONE3_PILOTING_CMD_FLATTRIM)); err != nil { + return err + } cmd.Write(tmp.Bytes()) @@ -344,7 +352,9 @@ func (b *Bebop) GenerateAllStates() error { cmd.WriteByte(ARCOMMANDS_ID_COMMON_CLASS_COMMON) tmp := &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, uint16(ARCOMMANDS_ID_COMMON_COMMON_CMD_ALLSTATES)) + if err := binary.Write(tmp, binary.LittleEndian, uint16(ARCOMMANDS_ID_COMMON_COMMON_CMD_ALLSTATES)); err != nil { + return err + } cmd.Write(tmp.Bytes()) @@ -363,7 +373,9 @@ func (b *Bebop) TakeOff() error { cmd.WriteByte(ARCOMMANDS_ID_ARDRONE3_CLASS_PILOTING) tmp := &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, uint16(ARCOMMANDS_ID_ARDRONE3_PILOTING_CMD_TAKEOFF)) + if err := binary.Write(tmp, binary.LittleEndian, uint16(ARCOMMANDS_ID_ARDRONE3_PILOTING_CMD_TAKEOFF)); err != nil { + return err + } cmd.Write(tmp.Bytes()) @@ -382,7 +394,9 @@ func (b *Bebop) Land() error { cmd.WriteByte(ARCOMMANDS_ID_ARDRONE3_CLASS_PILOTING) tmp := &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, uint16(ARCOMMANDS_ID_ARDRONE3_PILOTING_CMD_LANDING)) + if err := binary.Write(tmp, binary.LittleEndian, uint16(ARCOMMANDS_ID_ARDRONE3_PILOTING_CMD_LANDING)); err != nil { + return err + } cmd.Write(tmp.Bytes()) @@ -465,37 +479,50 @@ func (b *Bebop) generatePcmd() *bytes.Buffer { // cmd := &bytes.Buffer{} - tmp := &bytes.Buffer{} cmd.WriteByte(ARCOMMANDS_ID_PROJECT_ARDRONE3) cmd.WriteByte(ARCOMMANDS_ID_ARDRONE3_CLASS_PILOTING) - tmp = &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, uint16(ARCOMMANDS_ID_ARDRONE3_PILOTING_CMD_PCMD)) + tmp := &bytes.Buffer{} + if err := binary.Write(tmp, binary.LittleEndian, uint16(ARCOMMANDS_ID_ARDRONE3_PILOTING_CMD_PCMD)); err != nil { + panic(err) + } cmd.Write(tmp.Bytes()) tmp = &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, uint8(b.Pcmd.Flag)) + if err := binary.Write(tmp, binary.LittleEndian, uint8(b.Pcmd.Flag)); err != nil { + panic(err) + } cmd.Write(tmp.Bytes()) tmp = &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, int8(b.Pcmd.Roll)) + if err := binary.Write(tmp, binary.LittleEndian, int8(b.Pcmd.Roll)); err != nil { + panic(err) + } cmd.Write(tmp.Bytes()) tmp = &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, int8(b.Pcmd.Pitch)) + if err := binary.Write(tmp, binary.LittleEndian, int8(b.Pcmd.Pitch)); err != nil { + panic(err) + } cmd.Write(tmp.Bytes()) tmp = &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, int8(b.Pcmd.Yaw)) + if err := binary.Write(tmp, binary.LittleEndian, int8(b.Pcmd.Yaw)); err != nil { + panic(err) + } cmd.Write(tmp.Bytes()) tmp = &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, int8(b.Pcmd.Gaz)) + if err := binary.Write(tmp, binary.LittleEndian, int8(b.Pcmd.Gaz)); err != nil { + panic(err) + } cmd.Write(tmp.Bytes()) tmp = &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, uint32(b.Pcmd.Psi)) + if err := binary.Write(tmp, binary.LittleEndian, uint32(b.Pcmd.Psi)); err != nil { + panic(err) + } cmd.Write(tmp.Bytes()) return b.networkFrameGenerator(cmd, ARNETWORKAL_FRAME_TYPE_DATA, BD_NET_CD_NONACK_ID) @@ -565,15 +592,15 @@ func (b *Bebop) packetReceiver(buf []byte) { func (b *Bebop) StartRecording() error { buf := b.videoRecord(ARCOMMANDS_ARDRONE3_MEDIARECORD_VIDEO_RECORD_START) - b.write(b.networkFrameGenerator(buf, ARNETWORKAL_FRAME_TYPE_DATA, BD_NET_CD_NONACK_ID).Bytes()) - return nil + _, err := b.write(b.networkFrameGenerator(buf, ARNETWORKAL_FRAME_TYPE_DATA, BD_NET_CD_NONACK_ID).Bytes()) + return err } func (b *Bebop) StopRecording() error { buf := b.videoRecord(ARCOMMANDS_ARDRONE3_MEDIARECORD_VIDEO_RECORD_STOP) - b.write(b.networkFrameGenerator(buf, ARNETWORKAL_FRAME_TYPE_DATA, BD_NET_CD_NONACK_ID).Bytes()) - return nil + _, err := b.write(b.networkFrameGenerator(buf, ARNETWORKAL_FRAME_TYPE_DATA, BD_NET_CD_NONACK_ID).Bytes()) + return err } func (b *Bebop) videoRecord(state byte) *bytes.Buffer { @@ -587,15 +614,19 @@ func (b *Bebop) videoRecord(state byte) *bytes.Buffer { cmd.WriteByte(ARCOMMANDS_ID_ARDRONE3_CLASS_MEDIARECORD) tmp := &bytes.Buffer{} - binary.Write(tmp, + if err := binary.Write(tmp, binary.LittleEndian, uint16(ARCOMMANDS_ID_ARDRONE3_MEDIARECORD_CMD_VIDEO), - ) + ); err != nil { + panic(err) + } cmd.Write(tmp.Bytes()) tmp = &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, uint32(state)) + if err := binary.Write(tmp, binary.LittleEndian, uint32(state)); err != nil { + panic(err) + } cmd.Write(tmp.Bytes()) @@ -619,15 +650,19 @@ func (b *Bebop) HullProtection(protect bool) error { cmd.WriteByte(ARCOMMANDS_ID_ARDRONE3_CLASS_SPEEDSETTINGS) tmp := &bytes.Buffer{} - binary.Write(tmp, + if err := binary.Write(tmp, binary.LittleEndian, uint16(ARCOMMANDS_ID_ARDRONE3_SPEEDSETTINGS_CMD_HULLPROTECTION), - ) + ); err != nil { + return err + } cmd.Write(tmp.Bytes()) tmp = &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, bool2int8(protect)) + if err := binary.Write(tmp, binary.LittleEndian, bool2int8(protect)); err != nil { + return err + } cmd.Write(tmp.Bytes()) _, err := b.write(b.networkFrameGenerator(cmd, ARNETWORKAL_FRAME_TYPE_DATA, BD_NET_CD_NONACK_ID).Bytes()) @@ -645,15 +680,19 @@ func (b *Bebop) Outdoor(outdoor bool) error { cmd.WriteByte(ARCOMMANDS_ID_ARDRONE3_CLASS_SPEEDSETTINGS) tmp := &bytes.Buffer{} - binary.Write(tmp, + if err := binary.Write(tmp, binary.LittleEndian, uint16(ARCOMMANDS_ID_ARDRONE3_SPEEDSETTINGS_CMD_OUTDOOR), - ) + ); err != nil { + return err + } cmd.Write(tmp.Bytes()) tmp = &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, bool2int8(outdoor)) + if err := binary.Write(tmp, binary.LittleEndian, bool2int8(outdoor)); err != nil { + return err + } cmd.Write(tmp.Bytes()) _, err := b.write(b.networkFrameGenerator(cmd, ARNETWORKAL_FRAME_TYPE_DATA, BD_NET_CD_NONACK_ID).Bytes()) @@ -667,15 +706,19 @@ func (b *Bebop) VideoEnable(enable bool) error { cmd.WriteByte(ARCOMMANDS_ID_ARDRONE3_CLASS_MEDIASTREAMING) tmp := &bytes.Buffer{} - binary.Write(tmp, + if err := binary.Write(tmp, binary.LittleEndian, uint16(ARCOMMANDS_ID_ARDRONE3_MEDIASTREAMING_CMD_VIDEOENABLE), - ) + ); err != nil { + return err + } cmd.Write(tmp.Bytes()) tmp = &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, bool2int8(enable)) + if err := binary.Write(tmp, binary.LittleEndian, bool2int8(enable)); err != nil { + return err + } cmd.Write(tmp.Bytes()) _, err := b.write(b.networkFrameGenerator(cmd, ARNETWORKAL_FRAME_TYPE_DATA, BD_NET_CD_NONACK_ID).Bytes()) @@ -689,15 +732,19 @@ func (b *Bebop) VideoStreamMode(mode int8) error { cmd.WriteByte(ARCOMMANDS_ID_ARDRONE3_CLASS_MEDIASTREAMING) tmp := &bytes.Buffer{} - binary.Write(tmp, + if err := binary.Write(tmp, binary.LittleEndian, uint16(ARCOMMANDS_ID_ARDRONE3_MEDIASTREAMING_CMD_VIDEOSTREAMMODE), - ) + ); err != nil { + return err + } cmd.Write(tmp.Bytes()) tmp = &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, mode) + if err := binary.Write(tmp, binary.LittleEndian, mode); err != nil { + return err + } cmd.Write(tmp.Bytes()) _, err := b.write(b.networkFrameGenerator(cmd, ARNETWORKAL_FRAME_TYPE_DATA, BD_NET_CD_NONACK_ID).Bytes()) @@ -781,15 +828,21 @@ func (b *Bebop) createARStreamACK(frame ARStreamFrame) *bytes.Buffer { ackPacket := &bytes.Buffer{} tmp := &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, uint16(b.tmpFrame.arstreamACK.FrameNumber)) + if err := binary.Write(tmp, binary.LittleEndian, uint16(b.tmpFrame.arstreamACK.FrameNumber)); err != nil { + panic(err) + } ackPacket.Write(tmp.Bytes()) tmp = &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, uint64(b.tmpFrame.arstreamACK.HighPacketsAck)) + if err := binary.Write(tmp, binary.LittleEndian, uint64(b.tmpFrame.arstreamACK.HighPacketsAck)); err != nil { + panic(err) + } ackPacket.Write(tmp.Bytes()) tmp = &bytes.Buffer{} - binary.Write(tmp, binary.LittleEndian, uint64(b.tmpFrame.arstreamACK.LowPacketsAck)) + if err := binary.Write(tmp, binary.LittleEndian, uint64(b.tmpFrame.arstreamACK.LowPacketsAck)); err != nil { + panic(err) + } ackPacket.Write(tmp.Bytes()) return b.networkFrameGenerator(ackPacket, ARNETWORKAL_FRAME_TYPE_DATA, BD_NET_CD_VIDEO_ACK_ID) diff --git a/platforms/parrot/minidrone/minidrone_driver.go b/platforms/parrot/minidrone/minidrone_driver.go index 812be61b1..e1d3a1183 100644 --- a/platforms/parrot/minidrone/minidrone_driver.go +++ b/platforms/parrot/minidrone/minidrone_driver.go @@ -25,8 +25,8 @@ type Driver struct { const ( // BLE services - droneCommandService = "9a66fa000800919111e4012d1540cb8e" - droneNotificationService = "9a66fb000800919111e4012d1540cb8e" + //droneCommandService = "9a66fa000800919111e4012d1540cb8e" + //droneNotificationService = "9a66fb000800919111e4012d1540cb8e" // send characteristics pcmdCharacteristic = "9a66fa0a0800919111e4012d1540cb8e" @@ -151,93 +151,86 @@ func (b *Driver) adaptor() ble.BLEConnector { } // Start tells driver to get ready to do work -func (b *Driver) Start() (err error) { +func (b *Driver) Start() error { b.adaptor().WithoutResponses(true) - b.Init() - b.FlatTrim() + if err := b.Init(); err != nil { + return err + } + if err := b.FlatTrim(); err != nil { + return err + } + b.StartPcmd() - b.FlatTrim() - return + return b.FlatTrim() } // Halt stops minidrone driver (void) -func (b *Driver) Halt() (err error) { - b.Land() - +func (b *Driver) Halt() error { + err := b.Land() time.Sleep(500 * time.Millisecond) - return + return err } // Init initializes the BLE insterfaces used by the Minidrone -func (b *Driver) Init() (err error) { - b.GenerateAllStates() +func (b *Driver) Init() error { + if err := b.GenerateAllStates(); err != nil { + return err + } // subscribe to battery notifications - b.adaptor().Subscribe(batteryCharacteristic, func(data []byte, e error) { + if err := b.adaptor().Subscribe(batteryCharacteristic, func(data []byte, e error) { b.Publish(b.Event(Battery), data[len(data)-1]) - }) + }); err != nil { + return err + } // subscribe to flying status notifications - b.adaptor().Subscribe(flightStatusCharacteristic, func(data []byte, e error) { + return b.adaptor().Subscribe(flightStatusCharacteristic, func(data []byte, e error) { b.processFlightStatus(data) }) - - return } // GenerateAllStates sets up all the default states aka settings on the drone -func (b *Driver) GenerateAllStates() (err error) { +func (b *Driver) GenerateAllStates() error { b.stepsfa0b++ buf := []byte{0x04, byte(b.stepsfa0b), 0x00, 0x04, 0x01, 0x00, 0x32, 0x30, 0x31, 0x34, 0x2D, 0x31, 0x30, 0x2D, 0x32, 0x38, 0x00} - err = b.adaptor().WriteCharacteristic(commandCharacteristic, buf) - - return + return b.adaptor().WriteCharacteristic(commandCharacteristic, buf) } // TakeOff tells the Minidrone to takeoff -func (b *Driver) TakeOff() (err error) { +func (b *Driver) TakeOff() error { b.stepsfa0b++ buf := []byte{0x02, byte(b.stepsfa0b) & 0xff, 0x02, 0x00, 0x01, 0x00} - err = b.adaptor().WriteCharacteristic(commandCharacteristic, buf) - - return + return b.adaptor().WriteCharacteristic(commandCharacteristic, buf) } // Land tells the Minidrone to land -func (b *Driver) Land() (err error) { +func (b *Driver) Land() error { b.stepsfa0b++ buf := []byte{0x02, byte(b.stepsfa0b) & 0xff, 0x02, 0x00, 0x03, 0x00} - err = b.adaptor().WriteCharacteristic(commandCharacteristic, buf) - - return err + return b.adaptor().WriteCharacteristic(commandCharacteristic, buf) } // FlatTrim calibrates the Minidrone to use its current position as being level -func (b *Driver) FlatTrim() (err error) { +func (b *Driver) FlatTrim() error { b.stepsfa0b++ buf := []byte{0x02, byte(b.stepsfa0b) & 0xff, 0x02, 0x00, 0x00, 0x00} - err = b.adaptor().WriteCharacteristic(commandCharacteristic, buf) - - return err + return b.adaptor().WriteCharacteristic(commandCharacteristic, buf) } // Emergency sets the Minidrone into emergency mode -func (b *Driver) Emergency() (err error) { +func (b *Driver) Emergency() error { b.stepsfa0b++ buf := []byte{0x02, byte(b.stepsfa0b) & 0xff, 0x02, 0x00, 0x04, 0x00} - err = b.adaptor().WriteCharacteristic(priorityCharacteristic, buf) - - return err + return b.adaptor().WriteCharacteristic(priorityCharacteristic, buf) } // TakePicture tells the Minidrone to take a picture -func (b *Driver) TakePicture() (err error) { +func (b *Driver) TakePicture() error { b.stepsfa0b++ buf := []byte{0x02, byte(b.stepsfa0b) & 0xff, 0x02, 0x06, 0x01, 0x00} - err = b.adaptor().WriteCharacteristic(commandCharacteristic, buf) - - return err + return b.adaptor().WriteCharacteristic(commandCharacteristic, buf) } // StartPcmd starts the continuous Pcmd communication with the Minidrone @@ -374,22 +367,22 @@ func (b *Driver) Outdoor(outdoor bool) error { } // FrontFlip tells the drone to perform a front flip -func (b *Driver) FrontFlip() (err error) { +func (b *Driver) FrontFlip() error { return b.adaptor().WriteCharacteristic(commandCharacteristic, b.generateAnimation(0).Bytes()) } // BackFlip tells the drone to perform a backflip -func (b *Driver) BackFlip() (err error) { +func (b *Driver) BackFlip() error { return b.adaptor().WriteCharacteristic(commandCharacteristic, b.generateAnimation(1).Bytes()) } // RightFlip tells the drone to perform a flip to the right -func (b *Driver) RightFlip() (err error) { +func (b *Driver) RightFlip() error { return b.adaptor().WriteCharacteristic(commandCharacteristic, b.generateAnimation(2).Bytes()) } // LeftFlip tells the drone to perform a flip to the left -func (b *Driver) LeftFlip() (err error) { +func (b *Driver) LeftFlip() error { return b.adaptor().WriteCharacteristic(commandCharacteristic, b.generateAnimation(3).Bytes()) } @@ -401,11 +394,10 @@ func (b *Driver) LeftFlip() (err error) { // mode - either LightFixed, LightBlinked, or LightOscillated // intensity - Light intensity from 0 (OFF) to 100 (Max intensity). // Only used in LightFixed mode. -func (b *Driver) LightControl(id uint8, mode uint8, intensity uint8) (err error) { +func (b *Driver) LightControl(id uint8, mode uint8, intensity uint8) error { b.stepsfa0b++ buf := []byte{0x02, byte(b.stepsfa0b) & 0xff, 0x02, 0x10, 0x00, id, mode, intensity, 0x00} - err = b.adaptor().WriteCharacteristic(commandCharacteristic, buf) - return + return b.adaptor().WriteCharacteristic(commandCharacteristic, buf) } // ClawControl controls the claw on the Parrot Mambo @@ -413,22 +405,21 @@ func (b *Driver) LightControl(id uint8, mode uint8, intensity uint8) (err error) // // id - always 0 // mode - either ClawOpen or ClawClosed -func (b *Driver) ClawControl(id uint8, mode uint8) (err error) { +func (b *Driver) ClawControl(id uint8, mode uint8) error { b.stepsfa0b++ buf := []byte{0x02, byte(b.stepsfa0b) & 0xff, 0x02, 0x10, 0x01, id, mode, 0x00} - err = b.adaptor().WriteCharacteristic(commandCharacteristic, buf) - return + return b.adaptor().WriteCharacteristic(commandCharacteristic, buf) } // GunControl fires the gun on the Parrot Mambo // Params: // // id - always 0 -func (b *Driver) GunControl(id uint8) (err error) { +func (b *Driver) GunControl(id uint8) error { b.stepsfa0b++ buf := []byte{0x02, byte(b.stepsfa0b) & 0xff, 0x02, 0x10, 0x02, id, 0x00} - err = b.adaptor().WriteCharacteristic(commandCharacteristic, buf) - return + return b.adaptor().WriteCharacteristic(commandCharacteristic, buf) + } func (b *Driver) generateAnimation(direction int8) *bytes.Buffer { @@ -444,20 +435,48 @@ func (b *Driver) generatePcmd() *bytes.Buffer { pcmd := b.Pcmd cmd := &bytes.Buffer{} - binary.Write(cmd, binary.LittleEndian, int8(2)) - binary.Write(cmd, binary.LittleEndian, int8(b.stepsfa0a)) - binary.Write(cmd, binary.LittleEndian, int8(2)) - binary.Write(cmd, binary.LittleEndian, int8(0)) - binary.Write(cmd, binary.LittleEndian, int8(2)) - binary.Write(cmd, binary.LittleEndian, int8(0)) - binary.Write(cmd, binary.LittleEndian, int8(pcmd.Flag)) - binary.Write(cmd, binary.LittleEndian, int8(pcmd.Roll)) - binary.Write(cmd, binary.LittleEndian, int8(pcmd.Pitch)) - binary.Write(cmd, binary.LittleEndian, int8(pcmd.Yaw)) - binary.Write(cmd, binary.LittleEndian, int8(pcmd.Gaz)) - binary.Write(cmd, binary.LittleEndian, float32(pcmd.Psi)) - binary.Write(cmd, binary.LittleEndian, int16(0)) - binary.Write(cmd, binary.LittleEndian, int16(0)) + if err := binary.Write(cmd, binary.LittleEndian, int8(2)); err != nil { + panic(err) + } + if err := binary.Write(cmd, binary.LittleEndian, int8(b.stepsfa0a)); err != nil { + panic(err) + } + if err := binary.Write(cmd, binary.LittleEndian, int8(2)); err != nil { + panic(err) + } + if err := binary.Write(cmd, binary.LittleEndian, int8(0)); err != nil { + panic(err) + } + if err := binary.Write(cmd, binary.LittleEndian, int8(2)); err != nil { + panic(err) + } + if err := binary.Write(cmd, binary.LittleEndian, int8(0)); err != nil { + panic(err) + } + if err := binary.Write(cmd, binary.LittleEndian, int8(pcmd.Flag)); err != nil { + panic(err) + } + if err := binary.Write(cmd, binary.LittleEndian, int8(pcmd.Roll)); err != nil { + panic(err) + } + if err := binary.Write(cmd, binary.LittleEndian, int8(pcmd.Pitch)); err != nil { + panic(err) + } + if err := binary.Write(cmd, binary.LittleEndian, int8(pcmd.Yaw)); err != nil { + panic(err) + } + if err := binary.Write(cmd, binary.LittleEndian, int8(pcmd.Gaz)); err != nil { + panic(err) + } + if err := binary.Write(cmd, binary.LittleEndian, float32(pcmd.Psi)); err != nil { + panic(err) + } + if err := binary.Write(cmd, binary.LittleEndian, int16(0)); err != nil { + panic(err) + } + if err := binary.Write(cmd, binary.LittleEndian, int16(0)); err != nil { + panic(err) + } return cmd } diff --git a/platforms/particle/adaptor.go b/platforms/particle/adaptor.go index aed5da0d7..dbaaf0ca9 100644 --- a/platforms/particle/adaptor.go +++ b/platforms/particle/adaptor.go @@ -58,17 +58,13 @@ func (s *Adaptor) Name() string { return s.name } func (s *Adaptor) SetName(n string) { s.name = n } // Connect returns true if connection to Particle Photon or Electron is successful -func (s *Adaptor) Connect() (err error) { - return -} +func (s *Adaptor) Connect() error { return nil } // Finalize returns true if connection to Particle Photon or Electron is finalized successfully -func (s *Adaptor) Finalize() (err error) { - return -} +func (s *Adaptor) Finalize() error { return nil } // AnalogRead reads analog ping value using Particle cloud api -func (s *Adaptor) AnalogRead(pin string) (val int, err error) { +func (s *Adaptor) AnalogRead(pin string) (int, error) { params := url.Values{ "params": {pin}, "access_token": {s.AccessToken}, @@ -78,63 +74,61 @@ func (s *Adaptor) AnalogRead(pin string) (val int, err error) { resp, err := s.request("POST", url, params) if err == nil { - val = int(resp["return_value"].(float64)) - return + return int(resp["return_value"].(float64)), nil } return 0, err } // PwmWrite writes in pin using analog write api -func (s *Adaptor) PwmWrite(pin string, level byte) (err error) { +func (s *Adaptor) PwmWrite(pin string, level byte) error { return s.AnalogWrite(pin, level) } // AnalogWrite writes analog pin with specified level using Particle cloud api -func (s *Adaptor) AnalogWrite(pin string, level byte) (err error) { +func (s *Adaptor) AnalogWrite(pin string, level byte) error { params := url.Values{ "params": {fmt.Sprintf("%v,%v", pin, level)}, "access_token": {s.AccessToken}, } url := fmt.Sprintf("%v/analogwrite", s.deviceURL()) - _, err = s.request("POST", url, params) - return + _, err := s.request("POST", url, params) + return err } // DigitalWrite writes to a digital pin using Particle cloud api -func (s *Adaptor) DigitalWrite(pin string, level byte) (err error) { +func (s *Adaptor) DigitalWrite(pin string, level byte) error { params := url.Values{ "params": {fmt.Sprintf("%v,%v", pin, s.pinLevel(level))}, "access_token": {s.AccessToken}, } url := fmt.Sprintf("%v/digitalwrite", s.deviceURL()) - _, err = s.request("POST", url, params) + _, err := s.request("POST", url, params) return err } // DigitalRead reads from digital pin using Particle cloud api -func (s *Adaptor) DigitalRead(pin string) (val int, err error) { +func (s *Adaptor) DigitalRead(pin string) (int, error) { params := url.Values{ "params": {pin}, "access_token": {s.AccessToken}, } url := fmt.Sprintf("%v/digitalread", s.deviceURL()) resp, err := s.request("POST", url, params) - if err == nil { - val = int(resp["return_value"].(float64)) - return + if err != nil { + return -1, err } - return -1, err + + return int(resp["return_value"].(float64)), nil } // ServoWrite writes the 0-180 degree angle to the specified pin. // To use it requires installing the "tinker-servo" sketch on your // Particle device. not just the default "tinker". -func (s *Adaptor) ServoWrite(pin string, angle byte) (err error) { +func (s *Adaptor) ServoWrite(pin string, angle byte) error { if _, present := s.servoPins[pin]; !present { - err = s.servoPinOpen(pin) - if err != nil { - return + if err := s.servoPinOpen(pin); err != nil { + return err } } @@ -143,7 +137,7 @@ func (s *Adaptor) ServoWrite(pin string, angle byte) (err error) { "access_token": {s.AccessToken}, } url := fmt.Sprintf("%v/servoSet", s.deviceURL()) - _, err = s.request("POST", url, params) + _, err := s.request("POST", url, params) return err } @@ -209,7 +203,7 @@ func (s *Adaptor) Variable(name string) (result string, err error) { // returns value from request. // Takes a String as the only argument and returns an Int. // If function is not defined in core, it will time out -func (s *Adaptor) Function(name string, args string) (val int, err error) { +func (s *Adaptor) Function(name string, args string) (int, error) { params := url.Values{ "args": {args}, "access_token": {s.AccessToken}, @@ -217,13 +211,11 @@ func (s *Adaptor) Function(name string, args string) (val int, err error) { url := fmt.Sprintf("%s/%s", s.deviceURL(), name) resp, err := s.request("POST", url, params) - if err != nil { return -1, err } - val = int(resp["return_value"].(float64)) - return + return int(resp["return_value"].(float64)), nil } // setAPIServer sets Particle cloud api server, this can be used to change from default api.spark.io @@ -268,7 +260,9 @@ func (s *Adaptor) request(method string, url string, params url.Values) (m map[s return } - json.Unmarshal(buf, &m) + if err := json.Unmarshal(buf, &m); err != nil { + return m, err + } if resp.Status != "200 OK" { err = fmt.Errorf("%v: error communicating to the Particle cloud", resp.Status) diff --git a/platforms/particle/adaptor_test.go b/platforms/particle/adaptor_test.go index b467606b6..0c55db12e 100644 --- a/platforms/particle/adaptor_test.go +++ b/platforms/particle/adaptor_test.go @@ -19,20 +19,20 @@ func createTestServer(handler func(w http.ResponseWriter, r *http.Request)) *htt return httptest.NewServer(http.HandlerFunc(handler)) } -func getDummyResponseForPath(path string, dummy_response string, t *testing.T) *httptest.Server { - dummy_data := []byte(dummy_response) +func getDummyResponseForPath(path string, dummyResponse string, t *testing.T) *httptest.Server { + dummyData := []byte(dummyResponse) return createTestServer(func(w http.ResponseWriter, r *http.Request) { actualPath := "/v1/devices" + path if r.URL.Path != actualPath { t.Errorf("Path doesn't match, expected %#v, got %#v", actualPath, r.URL.Path) } - w.Write(dummy_data) + _, _ = w.Write(dummyData) }) } -func getDummyResponseForPathWithParams(path string, params []string, dummy_response string, t *testing.T) *httptest.Server { - dummy_data := []byte(dummy_response) +func getDummyResponseForPathWithParams(path string, params []string, dummyResponse string, t *testing.T) *httptest.Server { + dummyData := []byte(dummyResponse) return createTestServer(func(w http.ResponseWriter, r *http.Request) { actualPath := "/v1/devices" + path @@ -40,14 +40,14 @@ func getDummyResponseForPathWithParams(path string, params []string, dummy_respo t.Errorf("Path doesn't match, expected %#v, got %#v", actualPath, r.URL.Path) } - r.ParseForm() + _ = r.ParseForm() for key, value := range params { if r.Form["params"][key] != value { t.Error("Expected param to be " + r.Form["params"][key] + " but was " + value) } } - w.Write(dummy_data) + _, _ = w.Write(dummyData) }) } @@ -93,7 +93,7 @@ func TestAdaptorConnect(t *testing.T) { func TestAdaptorFinalize(t *testing.T) { a := initTestAdaptor() - a.Connect() + _ = a.Connect() gobottest.Assert(t, a.Finalize(), nil) } @@ -134,7 +134,7 @@ func TestAdaptorPwmWrite(t *testing.T) { defer testServer.Close() a.setAPIServer(testServer.URL) - a.PwmWrite("A1", 1) + _ = a.PwmWrite("A1", 1) } func TestAdaptorAnalogWrite(t *testing.T) { @@ -146,7 +146,7 @@ func TestAdaptorAnalogWrite(t *testing.T) { defer testServer.Close() a.setAPIServer(testServer.URL) - a.AnalogWrite("A1", 1) + _ = a.AnalogWrite("A1", 1) } func TestAdaptorDigitalWrite(t *testing.T) { @@ -158,7 +158,7 @@ func TestAdaptorDigitalWrite(t *testing.T) { testServer := getDummyResponseForPathWithParams("/"+a.DeviceID+"/digitalwrite", params, response, t) a.setAPIServer(testServer.URL) - a.DigitalWrite("D7", 1) + _ = a.DigitalWrite("D7", 1) testServer.Close() // When LOW @@ -168,7 +168,7 @@ func TestAdaptorDigitalWrite(t *testing.T) { defer testServer.Close() a.setAPIServer(testServer.URL) - a.DigitalWrite("D7", 0) + _ = a.DigitalWrite("D7", 0) } func TestAdaptorServoOpen(t *testing.T) { @@ -180,7 +180,7 @@ func TestAdaptorServoOpen(t *testing.T) { defer testServer.Close() a.setAPIServer(testServer.URL) - a.servoPinOpen("1") + _ = a.servoPinOpen("1") } func TestAdaptorServoWrite(t *testing.T) { @@ -192,7 +192,7 @@ func TestAdaptorServoWrite(t *testing.T) { defer testServer.Close() a.setAPIServer(testServer.URL) - a.ServoWrite("1", 128) + _ = a.ServoWrite("1", 128) } func TestAdaptorDigitalRead(t *testing.T) { @@ -369,15 +369,6 @@ func TestAdaptorPostToparticle(t *testing.T) { } } -type testEventSource struct { - event string - data string -} - -func (testEventSource) Id() string { return "" } -func (t testEventSource) Event() string { return t.event } -func (t testEventSource) Data() string { return t.data } - func TestAdaptorEventStream(t *testing.T) { a := initTestAdaptor() var url string @@ -385,13 +376,13 @@ func TestAdaptorEventStream(t *testing.T) { url = u return nil, nil, nil } - a.EventStream("all", "ping") + _, _ = a.EventStream("all", "ping") gobottest.Assert(t, url, "https://api.particle.io/v1/events/ping?access_token=token") - a.EventStream("devices", "ping") + _, _ = a.EventStream("devices", "ping") gobottest.Assert(t, url, "https://api.particle.io/v1/devices/events/ping?access_token=token") - a.EventStream("device", "ping") + _, _ = a.EventStream("device", "ping") gobottest.Assert(t, url, "https://api.particle.io/v1/devices/myDevice/events/ping?access_token=token") _, err := a.EventStream("nothing", "ping") diff --git a/platforms/pebble/pebble_driver_test.go b/platforms/pebble/pebble_driver_test.go index 40023fd9c..cbf0cd695 100644 --- a/platforms/pebble/pebble_driver_test.go +++ b/platforms/pebble/pebble_driver_test.go @@ -39,7 +39,7 @@ func TestDriver(t *testing.T) { gobottest.Assert(t, d.PendingMessage(), "World") gobottest.Assert(t, d.PendingMessage(), "") - d.On(d.Event("button"), func(data interface{}) { + _ = d.On(d.Event("button"), func(data interface{}) { sem <- true }) @@ -51,7 +51,7 @@ func TestDriver(t *testing.T) { t.Errorf("Button Event was not published") } - d.On(d.Event("accel"), func(data interface{}) { + _ = d.On(d.Event("accel"), func(data interface{}) { sem <- true }) diff --git a/platforms/raspi/raspi_adaptor.go b/platforms/raspi/raspi_adaptor.go index 839f54091..19414926a 100644 --- a/platforms/raspi/raspi_adaptor.go +++ b/platforms/raspi/raspi_adaptor.go @@ -34,8 +34,7 @@ type Adaptor struct { *adaptors.DigitalPinsAdaptor *adaptors.I2cBusAdaptor *adaptors.SpiBusAdaptor - spiDefaultMaxSpeed int64 - PiBlasterPeriod uint32 + PiBlasterPeriod uint32 } // NewAdaptor creates a Raspi Adaptor @@ -236,7 +235,9 @@ func (c *Adaptor) pwmPin(id string) (gobot.PWMPinner, error) { return nil, err } pin = NewPWMPin(c.sys, "/dev/pi-blaster", strconv.Itoa(i)) - pin.SetPeriod(c.PiBlasterPeriod) + if err := pin.SetPeriod(c.PiBlasterPeriod); err != nil { + return nil, err + } c.pwmPins[id] = pin } diff --git a/platforms/raspi/raspi_adaptor_test.go b/platforms/raspi/raspi_adaptor_test.go index 28e71c9ba..560fed662 100644 --- a/platforms/raspi/raspi_adaptor_test.go +++ b/platforms/raspi/raspi_adaptor_test.go @@ -32,7 +32,7 @@ var _ spi.Connector = (*Adaptor)(nil) func initTestAdaptorWithMockedFilesystem(mockPaths []string) (*Adaptor, *system.MockFilesystem) { a := NewAdaptor() fs := a.sys.UseMockFilesystem(mockPaths) - a.Connect() + _ = a.Connect() return a, fs } @@ -99,10 +99,10 @@ func TestFinalize(t *testing.T) { } a, _ := initTestAdaptorWithMockedFilesystem(mockedPaths) - a.DigitalWrite("3", 1) - a.PwmWrite("7", 255) + _ = a.DigitalWrite("3", 1) + _ = a.PwmWrite("7", 255) - a.GetI2cConnection(0xff, 0) + _, _ = a.GetI2cConnection(0xff, 0) gobottest.Assert(t, a.Finalize(), nil) } @@ -179,7 +179,7 @@ func TestDigitalPinConcurrency(t *testing.T) { pinAsString := strconv.Itoa(i) go func(pin string) { defer wg.Done() - a.DigitalPin(pin) + _, _ = a.DigitalPin(pin) }(pinAsString) } diff --git a/platforms/rockpi/rockpi_adaptor.go b/platforms/rockpi/rockpi_adaptor.go index ae2800307..321b7a688 100644 --- a/platforms/rockpi/rockpi_adaptor.go +++ b/platforms/rockpi/rockpi_adaptor.go @@ -32,7 +32,6 @@ type Adaptor struct { *adaptors.DigitalPinsAdaptor *adaptors.I2cBusAdaptor *adaptors.SpiBusAdaptor - spiDefaultMaxSpeed int64 } // NewAdaptor creates a RockPi Adaptor diff --git a/platforms/rockpi/rockpi_adaptor_test.go b/platforms/rockpi/rockpi_adaptor_test.go index 7ce572ab6..1e3186298 100644 --- a/platforms/rockpi/rockpi_adaptor_test.go +++ b/platforms/rockpi/rockpi_adaptor_test.go @@ -11,7 +11,7 @@ import ( func initTestAdaptorWithMockedFilesystem(mockPaths []string) (*Adaptor, *system.MockFilesystem) { a := NewAdaptor() fs := a.sys.UseMockFilesystem(mockPaths) - a.Connect() + _ = a.Connect() return a, fs } diff --git a/platforms/sphero/ollie/ollie_driver.go b/platforms/sphero/ollie/ollie_driver.go index e8c406d92..eb4f29a18 100644 --- a/platforms/sphero/ollie/ollie_driver.go +++ b/platforms/sphero/ollie/ollie_driver.go @@ -29,8 +29,8 @@ type Driver struct { const ( // bluetooth service IDs - spheroBLEService = "22bb746f2bb075542d6f726568705327" - robotControlService = "22bb746f2ba075542d6f726568705327" + //spheroBLEService = "22bb746f2bb075542d6f726568705327" + //robotControlService = "22bb746f2ba075542d6f726568705327" // BLE characteristic IDs wakeCharacteristic = "22bb746f2bbf75542d6f726568705327" @@ -121,8 +121,10 @@ func (b *Driver) adaptor() ble.BLEConnector { } // Start tells driver to get ready to do work -func (b *Driver) Start() (err error) { - b.Init() +func (b *Driver) Start() error { + if err := b.Init(); err != nil { + return err + } // send commands go func() { @@ -137,74 +139,77 @@ func (b *Driver) Start() (err error) { go func() { for { - b.adaptor().ReadCharacteristic(responseCharacteristic) + if _, err := b.adaptor().ReadCharacteristic(responseCharacteristic); err != nil { + panic(err) + } time.Sleep(100 * time.Millisecond) } }() b.ConfigureCollisionDetection(DefaultCollisionConfig()) - return + return nil } // Halt stops Ollie driver (void) -func (b *Driver) Halt() (err error) { +func (b *Driver) Halt() error { b.Sleep() time.Sleep(750 * time.Microsecond) - return + return nil } // Init is used to initialize the Ollie -func (b *Driver) Init() (err error) { - b.AntiDOSOff() - b.SetTXPower(7) - b.Wake() +func (b *Driver) Init() error { + if err := b.AntiDOSOff(); err != nil { + return err + } + if err := b.SetTXPower(7); err != nil { + return err + } + if err := b.Wake(); err != nil { + return err + } // subscribe to Sphero response notifications - b.adaptor().Subscribe(responseCharacteristic, b.HandleResponses) - - return + return b.adaptor().Subscribe(responseCharacteristic, b.HandleResponses) } // AntiDOSOff turns off Anti-DOS code so we can control Ollie -func (b *Driver) AntiDOSOff() (err error) { +func (b *Driver) AntiDOSOff() error { str := "011i3" buf := &bytes.Buffer{} buf.WriteString(str) - err = b.adaptor().WriteCharacteristic(antiDosCharacteristic, buf.Bytes()) - if err != nil { + if err := b.adaptor().WriteCharacteristic(antiDosCharacteristic, buf.Bytes()); err != nil { fmt.Println("AntiDOSOff error:", err) return err } - return + return nil } // Wake wakes Ollie up so we can play -func (b *Driver) Wake() (err error) { +func (b *Driver) Wake() error { buf := []byte{0x01} - err = b.adaptor().WriteCharacteristic(wakeCharacteristic, buf) - if err != nil { + if err := b.adaptor().WriteCharacteristic(wakeCharacteristic, buf); err != nil { fmt.Println("Wake error:", err) return err } - return + return nil } // SetTXPower sets transmit level -func (b *Driver) SetTXPower(level int) (err error) { +func (b *Driver) SetTXPower(level int) error { buf := []byte{byte(level)} - err = b.adaptor().WriteCharacteristic(txPowerCharacteristic, buf) - if err != nil { + if err := b.adaptor().WriteCharacteristic(txPowerCharacteristic, buf); err != nil { fmt.Println("SetTXLevel error:", err) return err } - return + return nil } // HandleResponses handles responses returned from Ollie @@ -270,7 +275,9 @@ func (b *Driver) handleDataStreaming(data []byte) { //only difference in communication is that the "newer" spheros use BLE for communinations var dataPacket DataStreamingPacket buffer := bytes.NewBuffer(data[5:]) // skip header - binary.Read(buffer, binary.BigEndian, &dataPacket) + if err := binary.Read(buffer, binary.BigEndian, &dataPacket); err != nil { + panic(err) + } b.Publish(SensorData, dataPacket) } @@ -344,17 +351,19 @@ func (b *Driver) ConfigureCollisionDetection(cc sphero.CollisionConfig) { } // SetDataStreamingConfig passes the config to the sphero to stream sensor data -func (b *Driver) SetDataStreamingConfig(d sphero.DataStreamingConfig) { +func (b *Driver) SetDataStreamingConfig(d sphero.DataStreamingConfig) error { buf := new(bytes.Buffer) - binary.Write(buf, binary.BigEndian, d) + if err := binary.Write(buf, binary.BigEndian, d); err != nil { + return err + } b.PacketChannel() <- b.craftPacket(buf.Bytes(), 0x02, 0x11) + return nil } -func (b *Driver) write(packet *Packet) (err error) { +func (b *Driver) write(packet *Packet) error { buf := append(packet.Header, packet.Body...) buf = append(buf, packet.Checksum) - err = b.adaptor().WriteCharacteristic(commandsCharacteristic, buf) - if err != nil { + if err := b.adaptor().WriteCharacteristic(commandsCharacteristic, buf); err != nil { fmt.Println("send command error:", err) return err } @@ -362,7 +371,7 @@ func (b *Driver) write(packet *Packet) (err error) { b.mtx.Lock() defer b.mtx.Unlock() b.seq++ - return + return nil } func (b *Driver) craftPacket(body []uint8, did byte, cid byte) *Packet { @@ -381,7 +390,9 @@ func (b *Driver) handlePowerStateDetected(data []uint8) { var dataPacket PowerStatePacket buffer := bytes.NewBuffer(data[5:]) // skip header - binary.Read(buffer, binary.BigEndian, &dataPacket) + if err := binary.Read(buffer, binary.BigEndian, &dataPacket); err != nil { + panic(err) + } b.powerstateCallback(dataPacket) } @@ -454,7 +465,9 @@ func (b *Driver) handleCollisionDetected(data []uint8) { var collision sphero.CollisionPacket buffer := bytes.NewBuffer(b.collisionResponse[5:]) // skip header - binary.Read(buffer, binary.BigEndian, &collision) + if err := binary.Read(buffer, binary.BigEndian, &collision); err != nil { + panic(err) + } b.collisionResponse = nil // clear the current response b.Publish(Collision, collision) diff --git a/platforms/sphero/ollie/ollie_driver_test.go b/platforms/sphero/ollie/ollie_driver_test.go index de020a7a9..847c48dcf 100644 --- a/platforms/sphero/ollie/ollie_driver_test.go +++ b/platforms/sphero/ollie/ollie_driver_test.go @@ -2,7 +2,6 @@ package ollie import ( "fmt" - "math" "strconv" "testing" "time" @@ -63,10 +62,10 @@ func TestLocatorData(t *testing.T) { func TestDataStreaming(t *testing.T) { d := initTestOllieDriver() - d.SetDataStreamingConfig(sphero.DefaultDataStreamingConfig()) + _ = d.SetDataStreamingConfig(sphero.DefaultDataStreamingConfig()) response := false - d.On("sensordata", func(data interface{}) { + _ = d.On("sensordata", func(data interface{}) { cont := data.(DataStreamingPacket) fmt.Printf("got streaming packet: %+v \n", cont) gobottest.Assert(t, cont.RawAccX, int16(10)) @@ -100,14 +99,3 @@ func TestDataStreaming(t *testing.T) { t.Error("no response recieved") } } - -func parseBytes(s string) (f byte) { - i, err := strconv.ParseUint(s, 16, 32) - if err != nil { - return - } - - f = byte(math.Float32frombits(uint32(i))) - - return -} diff --git a/platforms/sphero/sphero_adaptor.go b/platforms/sphero/sphero_adaptor.go index 51dc380fa..762662a46 100644 --- a/platforms/sphero/sphero_adaptor.go +++ b/platforms/sphero/sphero_adaptor.go @@ -57,7 +57,9 @@ func (a *Adaptor) Connect() (err error) { // Returns true on Successful reconnection func (a *Adaptor) Reconnect() (err error) { if a.connected { - a.Disconnect() + if err := a.Disconnect(); err != nil { + return err + } } return a.Connect() } diff --git a/platforms/sphero/sphero_adaptor_test.go b/platforms/sphero/sphero_adaptor_test.go index 56a1b01ce..cd9403359 100644 --- a/platforms/sphero/sphero_adaptor_test.go +++ b/platforms/sphero/sphero_adaptor_test.go @@ -69,19 +69,19 @@ func TestSpheroAdaptor(t *testing.T) { func TestSpheroAdaptorReconnect(t *testing.T) { a, _ := initTestSpheroAdaptor() - a.Connect() + _ = a.Connect() gobottest.Assert(t, a.connected, true) - a.Reconnect() + _ = a.Reconnect() gobottest.Assert(t, a.connected, true) - a.Disconnect() + _ = a.Disconnect() gobottest.Assert(t, a.connected, false) - a.Reconnect() + _ = a.Reconnect() gobottest.Assert(t, a.connected, true) } func TestSpheroAdaptorFinalize(t *testing.T) { a, rwc := initTestSpheroAdaptor() - a.Connect() + _ = a.Connect() gobottest.Assert(t, a.Finalize(), nil) rwc.testAdaptorClose = func() error { diff --git a/platforms/sphero/sphero_driver.go b/platforms/sphero/sphero_driver.go index fb2bc2702..04b74f426 100644 --- a/platforms/sphero/sphero_driver.go +++ b/platforms/sphero/sphero_driver.go @@ -295,7 +295,9 @@ func (s *SpheroDriver) Roll(speed uint8, heading uint16) { // ConfigureLocator configures and enables the Locator func (s *SpheroDriver) ConfigureLocator(d LocatorConfig) { buf := new(bytes.Buffer) - binary.Write(buf, binary.BigEndian, d) + if err := binary.Write(buf, binary.BigEndian, d); err != nil { + panic(err) + } s.packetChannel <- s.craftPacket(buf.Bytes(), 0x02, 0x13) } @@ -303,7 +305,9 @@ func (s *SpheroDriver) ConfigureLocator(d LocatorConfig) { // SetDataStreaming enables sensor data streaming func (s *SpheroDriver) SetDataStreaming(d DataStreamingConfig) { buf := new(bytes.Buffer) - binary.Write(buf, binary.BigEndian, d) + if err := binary.Write(buf, binary.BigEndian, d); err != nil { + panic(err) + } s.packetChannel <- s.craftPacket(buf.Bytes(), 0x02, 0x11) } @@ -329,7 +333,9 @@ func (s *SpheroDriver) handleCollisionDetected(data []uint8) { } var collision CollisionPacket buffer := bytes.NewBuffer(data[5:]) // skip header - binary.Read(buffer, binary.BigEndian, &collision) + if err := binary.Read(buffer, binary.BigEndian, &collision); err != nil { + panic(err) + } s.Publish(Collision, collision) } @@ -340,7 +346,9 @@ func (s *SpheroDriver) handleDataStreaming(data []uint8) { } var dataPacket DataStreamingPacket buffer := bytes.NewBuffer(data[5:]) // skip header - binary.Read(buffer, binary.BigEndian, &dataPacket) + if err := binary.Read(buffer, binary.BigEndian, &dataPacket); err != nil { + panic(err) + } s.Publish(SensorData, dataPacket) } diff --git a/platforms/sphero/sphero_driver_test.go b/platforms/sphero/sphero_driver_test.go index f115afa42..28a3d79f7 100644 --- a/platforms/sphero/sphero_driver_test.go +++ b/platforms/sphero/sphero_driver_test.go @@ -14,7 +14,7 @@ var _ gobot.Driver = (*SpheroDriver)(nil) func initTestSpheroDriver() *SpheroDriver { a, _ := initTestSpheroAdaptor() - a.Connect() + _ = a.Connect() return NewSpheroDriver(a) } @@ -100,7 +100,7 @@ func TestSpheroDriverSetDataStreaming(t *testing.T) { data := <-d.packetChannel buf := new(bytes.Buffer) - binary.Write(buf, binary.BigEndian, DefaultDataStreamingConfig()) + _ = binary.Write(buf, binary.BigEndian, DefaultDataStreamingConfig()) gobottest.Assert(t, data.body, buf.Bytes()) @@ -118,7 +118,7 @@ func TestSpheroDriverSetDataStreaming(t *testing.T) { dconfig := DataStreamingConfig{N: 100, M: 200, Mask: 300, Pcnt: 255, Mask2: 400} buf = new(bytes.Buffer) - binary.Write(buf, binary.BigEndian, dconfig) + _ = binary.Write(buf, binary.BigEndian, dconfig) gobottest.Assert(t, data.body, buf.Bytes()) } @@ -129,7 +129,7 @@ func TestConfigureLocator(t *testing.T) { data := <-d.packetChannel buf := new(bytes.Buffer) - binary.Write(buf, binary.BigEndian, DefaultLocatorConfig()) + _ = binary.Write(buf, binary.BigEndian, DefaultLocatorConfig()) gobottest.Assert(t, data.body, buf.Bytes()) @@ -146,7 +146,7 @@ func TestConfigureLocator(t *testing.T) { lconfig := LocatorConfig{Flags: 1, X: 100, Y: 100, YawTare: 0} buf = new(bytes.Buffer) - binary.Write(buf, binary.BigEndian, lconfig) + _ = binary.Write(buf, binary.BigEndian, lconfig) gobottest.Assert(t, data.body, buf.Bytes()) } diff --git a/platforms/tinkerboard/adaptor.go b/platforms/tinkerboard/adaptor.go index 1a5e182fd..8b1208a65 100644 --- a/platforms/tinkerboard/adaptor.go +++ b/platforms/tinkerboard/adaptor.go @@ -11,8 +11,6 @@ import ( ) const ( - debug = false - pwmInvertedIdentifier = "inversed" defaultI2cBusNumber = 1 diff --git a/platforms/tinkerboard/adaptor_test.go b/platforms/tinkerboard/adaptor_test.go index 2bbb4ab0a..c25ae6145 100644 --- a/platforms/tinkerboard/adaptor_test.go +++ b/platforms/tinkerboard/adaptor_test.go @@ -83,7 +83,7 @@ func TestDigitalIO(t *testing.T) { // only basic tests needed, further tests are done in "digitalpinsadaptor.go" a, fs := initTestAdaptorWithMockedFilesystem(gpioMockPaths) - a.DigitalWrite("7", 1) + _ = a.DigitalWrite("7", 1) gobottest.Assert(t, fs.Files[gpio17Path+"value"].Contents, "1") fs.Files[gpio160Path+"value"].Contents = "1" diff --git a/platforms/upboard/up2/adaptor_test.go b/platforms/upboard/up2/adaptor_test.go index ce93c8af0..83ac48334 100644 --- a/platforms/upboard/up2/adaptor_test.go +++ b/platforms/upboard/up2/adaptor_test.go @@ -63,14 +63,14 @@ func TestName(t *testing.T) { func TestDigitalIO(t *testing.T) { a, fs := initTestAdaptorWithMockedFilesystem(gpioMockPaths) - a.DigitalWrite("7", 1) + _ = a.DigitalWrite("7", 1) gobottest.Assert(t, fs.Files["/sys/class/gpio/gpio462/value"].Contents, "1") fs.Files["/sys/class/gpio/gpio432/value"].Contents = "1" i, _ := a.DigitalRead("13") gobottest.Assert(t, i, 1) - a.DigitalWrite("green", 1) + _ = a.DigitalWrite("green", 1) gobottest.Assert(t, fs.Files["/sys/class/leds/upboard:green:/brightness"].Contents, "1", diff --git a/robot.go b/robot.go index 765d06ae6..6aa1283bf 100644 --- a/robot.go +++ b/robot.go @@ -68,30 +68,30 @@ func (r *Robots) Len() int { return len(*r) } -// Start calls the Start method of each Robot in the collection -func (r *Robots) Start(args ...interface{}) (err error) { +// Start calls the Start method of each Robot in the collection. We return on first error. +func (r *Robots) Start(args ...interface{}) error { autoRun := true if args[0] != nil { autoRun = args[0].(bool) } for _, robot := range *r { - if rerr := robot.Start(autoRun); rerr != nil { - err = multierror.Append(err, rerr) - return + if err := robot.Start(autoRun); err != nil { + return err } } - return + return nil } -// Stop calls the Stop method of each Robot in the collection -func (r *Robots) Stop() (err error) { +// Stop calls the Stop method of each Robot in the collection. We try to stop all robots and +// collect the errors. +func (r *Robots) Stop() error { + var err error for _, robot := range *r { - if rerr := robot.Stop(); rerr != nil { - err = multierror.Append(err, rerr) - return + if e := robot.Stop(); e != nil { + err = multierror.Append(err, e) } } - return + return err } // Each enumerates through the Robots and calls specified callback function. @@ -104,10 +104,9 @@ func (r *Robots) Each(f func(*Robot)) { // NewRobot returns a new Robot. It supports the following optional params: // // name: string with the name of the Robot. A name will be automatically generated if no name is supplied. -// []Connection: Connections which are automatically started and stopped with the robot +// []Connection: Connections which are automatically started and stopped with the robot // []Device: Devices which are automatically started and stopped with the robot // func(): The work routine the robot will execute once all devices and connections have been initialized and started -// func NewRobot(v ...interface{}) *Robot { r := &Robot{ Name: fmt.Sprintf("%X", Rand(int(^uint(0)>>1))), @@ -156,22 +155,23 @@ func NewRobot(v ...interface{}) *Robot { return r } -// Start a Robot's Connections, Devices, and work. -func (r *Robot) Start(args ...interface{}) (err error) { +// Start a Robot's Connections, Devices, and work. We stop initialization of +// connections and devices on first error. +func (r *Robot) Start(args ...interface{}) error { if len(args) > 0 && args[0] != nil { r.AutoRun = args[0].(bool) } log.Println("Starting Robot", r.Name, "...") - if cerr := r.Connections().Start(); cerr != nil { - err = multierror.Append(err, cerr) + if err := r.Connections().Start(); err != nil { log.Println(err) - return + return err } - if derr := r.Devices().Start(); derr != nil { - err = multierror.Append(err, derr) + + if err := r.Devices().Start(); err != nil { log.Println(err) - return + return err } + if r.Work == nil { r.Work = func() {} } @@ -183,36 +183,36 @@ func (r *Robot) Start(args ...interface{}) (err error) { }() r.running.Store(true) - if r.AutoRun { - c := make(chan os.Signal, 1) - r.trap(c) - // waiting for interrupt coming on the channel - <-c - - // Stop calls the Stop method on itself, if we are "auto-running". - r.Stop() + if !r.AutoRun { + return nil } - return + c := make(chan os.Signal, 1) + r.trap(c) + + // waiting for interrupt coming on the channel + <-c + + // Stop calls the Stop method on itself, if we are "auto-running". + return r.Stop() } -// Stop stops a Robot's connections and Devices +// Stop stops a Robot's connections and devices. We try to stop all items and +// collect all errors. func (r *Robot) Stop() error { - var result error + var err error log.Println("Stopping Robot", r.Name, "...") - err := r.Devices().Halt() - if err != nil { - result = multierror.Append(result, err) + if e := r.Devices().Halt(); e != nil { + err = multierror.Append(err, e) } - err = r.Connections().Finalize() - if err != nil { - result = multierror.Append(result, err) + if e := r.Connections().Finalize(); e != nil { + err = multierror.Append(err, e) } r.done <- true r.running.Store(false) - return result + return err } // Running returns if the Robot is currently started or not diff --git a/system/digitalpin_bench_test.go b/system/digitalpin_bench_test.go index afc58df34..eb60722c6 100644 --- a/system/digitalpin_bench_test.go +++ b/system/digitalpin_bench_test.go @@ -15,10 +15,10 @@ func BenchmarkDigitalRead(b *testing.B) { a.UseMockFilesystem(mockPaths) pin := a.NewDigitalPin("", 10) - pin.Write(1) + _ = pin.Write(1) for i := 0; i < b.N; i++ { - pin.Read() + _, _ = pin.Read() } } diff --git a/system/digitalpin_sysfs.go b/system/digitalpin_sysfs.go index c4170d5b4..7516a49d6 100644 --- a/system/digitalpin_sysfs.go +++ b/system/digitalpin_sysfs.go @@ -64,8 +64,7 @@ func (d *digitalPinSysfs) DirectionBehavior() string { // Export sets the pin as exported with the configured direction func (d *digitalPinSysfs) Export() error { - err := d.reconfigure() - return err + return d.reconfigure() } // Unexport release the pin @@ -194,7 +193,7 @@ func (d *digitalPinSysfs) reconfigure() error { } if err != nil { - d.Unexport() + return d.Unexport() } return err diff --git a/system/fs_mock_test.go b/system/fs_mock_test.go index afc39c516..78b974ad6 100644 --- a/system/fs_mock_test.go +++ b/system/fs_mock_test.go @@ -77,7 +77,7 @@ func TestMockFilesystemWrite(t *testing.T) { // Never been read or written. gobottest.Assert(t, f1.Seq <= 0, true) - f2.WriteString("testing") + _, _ = f2.WriteString("testing") // Was written. gobottest.Assert(t, f1.Seq > 0, true) gobottest.Assert(t, f1.Contents, "testing") diff --git a/system/spi_gpio.go b/system/spi_gpio.go index ab0af7894..68c7c0016 100644 --- a/system/spi_gpio.go +++ b/system/spi_gpio.go @@ -4,6 +4,7 @@ import ( "fmt" "time" + "github.com/hashicorp/go-multierror" "gobot.io/x/gobot/v2" ) @@ -77,19 +78,28 @@ func (s *spiGpio) TxRx(tx []byte, rx []byte) error { // Close the SPI connection. Implements gobot.SpiSystemDevicer. func (s *spiGpio) Close() error { + var err error if s.sclkPin != nil { - s.sclkPin.Unexport() + if e := s.sclkPin.Unexport(); e != nil { + err = multierror.Append(err, e) + } } if s.mosiPin != nil { - s.mosiPin.Unexport() + if e := s.mosiPin.Unexport(); e != nil { + err = multierror.Append(err, e) + } } if s.misoPin != nil { - s.misoPin.Unexport() + if e := s.misoPin.Unexport(); e != nil { + err = multierror.Append(err, e) + } } if s.nssPin != nil { - s.nssPin.Unexport() + if e := s.nssPin.Unexport(); e != nil { + err = multierror.Append(err, e) + } } - return nil + return err } func (cfg *spiGpioConfig) String() string {