diff --git a/adaptor.go b/adaptor.go index f8c2c659c..9b1bcac6a 100644 --- a/adaptor.go +++ b/adaptor.go @@ -7,9 +7,9 @@ type Adaptor interface { // SetName sets the label for the Adaptor SetName(n string) // Connect initiates the Adaptor - Connect() []error + Connect() error // Finalize terminates the Adaptor - Finalize() []error + Finalize() error } // Porter is the interface that describes an adaptor's port diff --git a/api/helpers_test.go b/api/helpers_test.go index 18760b384..859f95f28 100644 --- a/api/helpers_test.go +++ b/api/helpers_test.go @@ -28,8 +28,8 @@ type testDriver struct { gobot.Eventer } -func (t *testDriver) Start() (errs []error) { return } -func (t *testDriver) Halt() (errs []error) { return } +func (t *testDriver) Start() (err error) { return } +func (t *testDriver) Halt() (err error) { return } func (t *testDriver) Name() string { return t.name } func (t *testDriver) SetName(n string) { t.name = n } func (t *testDriver) Pin() string { return t.pin } @@ -64,14 +64,14 @@ type testAdaptor struct { port string } -var testAdaptorConnect = func() (errs []error) { return } -var testAdaptorFinalize = func() (errs []error) { return } +var testAdaptorConnect = func() (err error) { return } +var testAdaptorFinalize = func() (err error) { return } -func (t *testAdaptor) Finalize() (errs []error) { return testAdaptorFinalize() } -func (t *testAdaptor) Connect() (errs []error) { return testAdaptorConnect() } -func (t *testAdaptor) Name() string { return t.name } -func (t *testAdaptor) SetName(n string) { t.name = n } -func (t *testAdaptor) Port() string { return t.port } +func (t *testAdaptor) Finalize() (err error) { return testAdaptorFinalize() } +func (t *testAdaptor) Connect() (err error) { return testAdaptorConnect() } +func (t *testAdaptor) Name() string { return t.name } +func (t *testAdaptor) SetName(n string) { t.name = n } +func (t *testAdaptor) Port() string { return t.port } func newTestAdaptor(name string, port string) *testAdaptor { return &testAdaptor{ diff --git a/cli/generate.go b/cli/generate.go index 175e9b418..947563205 100644 --- a/cli/generate.go +++ b/cli/generate.go @@ -175,9 +175,9 @@ func ({{.FirstLetter}} *{{.UpperName}}Adaptor) Name() string { return {{.FirstLe func ({{.FirstLetter}} *{{.UpperName}}Adaptor) SetName(name string) { {{.FirstLetter}}.name = name } -func ({{.FirstLetter}} *{{.UpperName}}Adaptor) Connect() []error { return nil } +func ({{.FirstLetter}} *{{.UpperName}}Adaptor) Connect() error { return nil } -func ({{.FirstLetter}} *{{.UpperName}}Adaptor) Finalize() []error { return nil } +func ({{.FirstLetter}} *{{.UpperName}}Adaptor) Finalize() error { return nil } func ({{.FirstLetter}} *{{.UpperName}}Adaptor) Ping() string { return "pong" } ` @@ -242,7 +242,7 @@ func ({{.FirstLetter}} *{{.UpperName}}Driver) Ping() string { return {{.FirstLetter}}.adaptor().Ping() } -func ({{.FirstLetter}} *{{.UpperName}}Driver) Start() []error { +func ({{.FirstLetter}} *{{.UpperName}}Driver) Start() error { go func() { for { {{.FirstLetter}}.Publish({{.FirstLetter}}.Event(Hello), {{.FirstLetter}}.Hello()) @@ -257,7 +257,7 @@ func ({{.FirstLetter}} *{{.UpperName}}Driver) Start() []error { return nil } -func ({{.FirstLetter}} *{{.UpperName}}Driver) Halt() []error { +func ({{.FirstLetter}} *{{.UpperName}}Driver) Halt() error { {{.FirstLetter}}.halt <- true return nil } diff --git a/connection.go b/connection.go index 06cf5f82c..75c8c037a 100644 --- a/connection.go +++ b/connection.go @@ -1,9 +1,10 @@ package gobot import ( - "fmt" "log" "reflect" + + multierror "github.com/hashicorp/go-multierror" ) // JSONConnection is a JSON representation of a Connection. @@ -39,7 +40,7 @@ func (c *Connections) Each(f func(Connection)) { } // Start calls Connect on each Connection in c -func (c *Connections) Start() (errs []error) { +func (c *Connections) Start() (err error) { log.Println("Starting connections...") for _, connection := range *c { info := "Starting connection " + connection.Name() @@ -50,25 +51,19 @@ func (c *Connections) Start() (errs []error) { log.Println(info + "...") - if errs = connection.Connect(); len(errs) > 0 { - for i, err := range errs { - errs[i] = fmt.Errorf("Connection %q: %v", connection.Name(), err) - } - return + if cerr := connection.Connect(); cerr != nil { + err = multierror.Append(err, cerr) } } - return + return err } // Finalize calls Finalize on each Connection in c -func (c *Connections) Finalize() (errs []error) { +func (c *Connections) Finalize() (err error) { for _, connection := range *c { - if cerrs := connection.Finalize(); cerrs != nil { - for i, err := range cerrs { - cerrs[i] = fmt.Errorf("Connection %q: %v", connection.Name(), err) - } - errs = append(errs, cerrs...) + if cerr := connection.Finalize(); cerr != nil { + err = multierror.Append(err, cerr) } } - return errs + return err } diff --git a/device.go b/device.go index d2368a20b..924a1f7de 100644 --- a/device.go +++ b/device.go @@ -1,9 +1,10 @@ package gobot import ( - "fmt" "log" "reflect" + + multierror "github.com/hashicorp/go-multierror" ) // JSONDevice is a JSON representation of a Device. @@ -52,7 +53,7 @@ func (d *Devices) Each(f func(Device)) { } // Start calls Start on each Device in d -func (d *Devices) Start() (errs []error) { +func (d *Devices) Start() (err error) { log.Println("Starting devices...") for _, device := range *d { info := "Starting device " + device.Name() @@ -62,25 +63,19 @@ func (d *Devices) Start() (errs []error) { } log.Println(info + "...") - if errs = device.Start(); len(errs) > 0 { - for i, err := range errs { - errs[i] = fmt.Errorf("Device %q: %v", device.Name(), err) - } - return + if derr := device.Start(); derr != nil { + err = multierror.Append(err, derr) } } - return + return err } // Halt calls Halt on each Device in d -func (d *Devices) Halt() (errs []error) { +func (d *Devices) Halt() (err error) { for _, device := range *d { - if derrs := device.Halt(); len(derrs) > 0 { - for i, err := range derrs { - derrs[i] = fmt.Errorf("Device %q: %v", device.Name(), err) - } - errs = append(errs, derrs...) + if derr := device.Halt(); derr != nil { + err = multierror.Append(err, derr) } } - return + return err } diff --git a/driver.go b/driver.go index 436b7cfa4..dcbad824f 100644 --- a/driver.go +++ b/driver.go @@ -7,9 +7,9 @@ type Driver interface { // SetName sets the label for the Driver SetName(s string) // Start initiates the Driver - Start() []error + Start() error // Halt terminates the Driver - Halt() []error + Halt() error // Connection returns the Connection assiciated with the Driver Connection() Connection } diff --git a/drivers/gpio/analog_sensor_driver.go b/drivers/gpio/analog_sensor_driver.go index cd4170e76..a2df8c5e4 100644 --- a/drivers/gpio/analog_sensor_driver.go +++ b/drivers/gpio/analog_sensor_driver.go @@ -55,7 +55,7 @@ func NewAnalogSensorDriver(a AnalogReader, pin string, v ...time.Duration) *Anal // Emits the Events: // Data int - Event is emitted on change and represents the current reading from the sensor. // Error error - Event is emitted on error reading from the sensor. -func (a *AnalogSensorDriver) Start() (errs []error) { +func (a *AnalogSensorDriver) Start() (err error) { value := 0 go func() { timer := time.NewTimer(a.interval) @@ -82,7 +82,7 @@ func (a *AnalogSensorDriver) Start() (errs []error) { } // Halt stops polling the analog sensor for new information -func (a *AnalogSensorDriver) Halt() (errs []error) { +func (a *AnalogSensorDriver) Halt() (err error) { a.halt <- true return } diff --git a/drivers/gpio/button_driver.go b/drivers/gpio/button_driver.go index 2ee451345..9f4c8a1e8 100644 --- a/drivers/gpio/button_driver.go +++ b/drivers/gpio/button_driver.go @@ -50,7 +50,7 @@ func NewButtonDriver(a DigitalReader, pin string, v ...time.Duration) *ButtonDri // Push int - On button push // Release int - On button release // Error error - On button error -func (b *ButtonDriver) Start() (errs []error) { +func (b *ButtonDriver) Start() (err error) { state := 0 go func() { for { @@ -72,7 +72,7 @@ func (b *ButtonDriver) Start() (errs []error) { } // Halt stops polling the button for new information -func (b *ButtonDriver) Halt() (errs []error) { +func (b *ButtonDriver) Halt() (err error) { b.halt <- true return } diff --git a/drivers/gpio/buzzer_driver.go b/drivers/gpio/buzzer_driver.go index 70bf6b105..e4bb3cbce 100644 --- a/drivers/gpio/buzzer_driver.go +++ b/drivers/gpio/buzzer_driver.go @@ -150,10 +150,10 @@ func NewBuzzerDriver(a DigitalWriter, pin string) *BuzzerDriver { } // Start implements the Driver interface -func (l *BuzzerDriver) Start() (errs []error) { return } +func (l *BuzzerDriver) Start() (err error) { return } // Halt implements the Driver interface -func (l *BuzzerDriver) Halt() (errs []error) { return } +func (l *BuzzerDriver) Halt() (err error) { return } // Name returns the BuzzerDrivers name func (l *BuzzerDriver) Name() string { return l.name } diff --git a/drivers/gpio/direct_pin_driver.go b/drivers/gpio/direct_pin_driver.go index 01e959fd4..c80b8520a 100644 --- a/drivers/gpio/direct_pin_driver.go +++ b/drivers/gpio/direct_pin_driver.go @@ -68,10 +68,10 @@ func (d *DirectPinDriver) Pin() string { return d.pin } func (d *DirectPinDriver) Connection() gobot.Connection { return d.connection } // Start implements the Driver interface -func (d *DirectPinDriver) Start() (errs []error) { return } +func (d *DirectPinDriver) Start() (err error) { return } // Halt implements the Driver interface -func (d *DirectPinDriver) Halt() (errs []error) { return } +func (d *DirectPinDriver) Halt() (err error) { return } // Turn Off pin func (d *DirectPinDriver) Off() (err error) { diff --git a/drivers/gpio/grove_temperature_sensor_driver.go b/drivers/gpio/grove_temperature_sensor_driver.go index e2ac01faf..ddcfa7282 100644 --- a/drivers/gpio/grove_temperature_sensor_driver.go +++ b/drivers/gpio/grove_temperature_sensor_driver.go @@ -52,7 +52,7 @@ func NewGroveTemperatureSensorDriver(a AnalogReader, pin string, v ...time.Durat // Emits the Events: // Data int - Event is emitted on change and represents the current temperature in celsius from the sensor. // Error error - Event is emitted on error reading from the sensor. -func (a *GroveTemperatureSensorDriver) Start() (errs []error) { +func (a *GroveTemperatureSensorDriver) Start() (err error) { thermistor := 3975.0 a.temperature = 0 @@ -80,7 +80,7 @@ func (a *GroveTemperatureSensorDriver) Start() (errs []error) { } // Halt stops polling the analog sensor for new information -func (a *GroveTemperatureSensorDriver) Halt() (errs []error) { +func (a *GroveTemperatureSensorDriver) Halt() (err error) { a.halt <- true return } diff --git a/drivers/gpio/helpers_test.go b/drivers/gpio/helpers_test.go index 795845fdd..644be3f0c 100644 --- a/drivers/gpio/helpers_test.go +++ b/drivers/gpio/helpers_test.go @@ -2,10 +2,10 @@ package gpio type gpioTestBareAdaptor struct{} -func (t *gpioTestBareAdaptor) Connect() (errs []error) { return } -func (t *gpioTestBareAdaptor) Finalize() (errs []error) { return } -func (t *gpioTestBareAdaptor) Name() string { return "" } -func (t *gpioTestBareAdaptor) SetName(n string) {} +func (t *gpioTestBareAdaptor) Connect() (err error) { return } +func (t *gpioTestBareAdaptor) Finalize() (err error) { return } +func (t *gpioTestBareAdaptor) Name() string { return "" } +func (t *gpioTestBareAdaptor) SetName(n string) {} type gpioTestDigitalWriter struct { gpioTestBareAdaptor @@ -49,11 +49,11 @@ func (t *gpioTestAdaptor) AnalogRead(string) (val int, err error) { func (t *gpioTestAdaptor) DigitalRead(string) (val int, err error) { return testAdaptorDigitalRead() } -func (t *gpioTestAdaptor) Connect() (errs []error) { return } -func (t *gpioTestAdaptor) Finalize() (errs []error) { return } -func (t *gpioTestAdaptor) Name() string { return t.name } -func (t *gpioTestAdaptor) SetName(n string) { t.name = n } -func (t *gpioTestAdaptor) Port() string { return t.port } +func (t *gpioTestAdaptor) Connect() (err error) { return } +func (t *gpioTestAdaptor) Finalize() (err error) { return } +func (t *gpioTestAdaptor) Name() string { return t.name } +func (t *gpioTestAdaptor) SetName(n string) { t.name = n } +func (t *gpioTestAdaptor) Port() string { return t.port } func newGpioTestAdaptor() *gpioTestAdaptor { return &gpioTestAdaptor{ diff --git a/drivers/gpio/led_driver.go b/drivers/gpio/led_driver.go index 167895623..9d261bc10 100644 --- a/drivers/gpio/led_driver.go +++ b/drivers/gpio/led_driver.go @@ -50,10 +50,10 @@ func NewLedDriver(a DigitalWriter, pin string) *LedDriver { } // Start implements the Driver interface -func (l *LedDriver) Start() (errs []error) { return } +func (l *LedDriver) Start() (err error) { return } // Halt implements the Driver interface -func (l *LedDriver) Halt() (errs []error) { return } +func (l *LedDriver) Halt() (err error) { return } // Name returns the LedDrivers name func (l *LedDriver) Name() string { return l.name } diff --git a/drivers/gpio/makey_button_driver.go b/drivers/gpio/makey_button_driver.go index 4a6f400c4..a688a559a 100644 --- a/drivers/gpio/makey_button_driver.go +++ b/drivers/gpio/makey_button_driver.go @@ -62,7 +62,7 @@ func (b *MakeyButtonDriver) Connection() gobot.Connection { return b.connection. // Push int - On button push // Release int - On button release // Error error - On button error -func (b *MakeyButtonDriver) Start() (errs []error) { +func (b *MakeyButtonDriver) Start() (err error) { state := 1 go func() { timer := time.NewTimer(b.interval) @@ -93,7 +93,7 @@ func (b *MakeyButtonDriver) Start() (errs []error) { } // Halt stops polling the makey button for new information -func (b *MakeyButtonDriver) Halt() (errs []error) { +func (b *MakeyButtonDriver) Halt() (err error) { b.halt <- true return } diff --git a/drivers/gpio/motor_driver.go b/drivers/gpio/motor_driver.go index 351e22708..39496b26d 100644 --- a/drivers/gpio/motor_driver.go +++ b/drivers/gpio/motor_driver.go @@ -42,10 +42,10 @@ func (m *MotorDriver) SetName(n string) { m.name = n } func (m *MotorDriver) Connection() gobot.Connection { return m.connection.(gobot.Connection) } // Start implements the Driver interface -func (m *MotorDriver) Start() (errs []error) { return } +func (m *MotorDriver) Start() (err error) { return } // Halt implements the Driver interface -func (m *MotorDriver) Halt() (errs []error) { return } +func (m *MotorDriver) Halt() (err error) { return } // Off turns the motor off or sets the motor to a 0 speed func (m *MotorDriver) Off() (err error) { diff --git a/drivers/gpio/pir_motion_driver.go b/drivers/gpio/pir_motion_driver.go index 4c95f74e7..7d929cb31 100644 --- a/drivers/gpio/pir_motion_driver.go +++ b/drivers/gpio/pir_motion_driver.go @@ -55,7 +55,7 @@ func NewPIRMotionDriver(a DigitalReader, pin string, v ...time.Duration) *PIRMot // just as long as motion is still being detected. // It will only send the MotionStopped event once, however, until // motion starts being detected again -func (p *PIRMotionDriver) Start() (errs []error) { +func (p *PIRMotionDriver) Start() (err error) { go func() { for { newValue, err := p.connection.DigitalRead(p.Pin()) @@ -86,7 +86,7 @@ func (p *PIRMotionDriver) Start() (errs []error) { } // Halt stops polling the button for new information -func (p *PIRMotionDriver) Halt() (errs []error) { +func (p *PIRMotionDriver) Halt() (err error) { p.halt <- true return } diff --git a/drivers/gpio/relay_driver.go b/drivers/gpio/relay_driver.go index 618dcb08a..261ffc766 100644 --- a/drivers/gpio/relay_driver.go +++ b/drivers/gpio/relay_driver.go @@ -42,10 +42,10 @@ func NewRelayDriver(a DigitalWriter, pin string) *RelayDriver { } // Start implements the Driver interface -func (l *RelayDriver) Start() (errs []error) { return } +func (l *RelayDriver) Start() (err error) { return } // Halt implements the Driver interface -func (l *RelayDriver) Halt() (errs []error) { return } +func (l *RelayDriver) Halt() (err error) { return } // Name returns the RelayDrivers name func (l *RelayDriver) Name() string { return l.name } diff --git a/drivers/gpio/rgb_led_driver.go b/drivers/gpio/rgb_led_driver.go index ab5c58cd0..a57828865 100644 --- a/drivers/gpio/rgb_led_driver.go +++ b/drivers/gpio/rgb_led_driver.go @@ -58,10 +58,10 @@ func NewRgbLedDriver(a DigitalWriter, redPin string, greenPin string, bluePin st } // Start implements the Driver interface -func (l *RgbLedDriver) Start() (errs []error) { return } +func (l *RgbLedDriver) Start() (err error) { return } // Halt implements the Driver interface -func (l *RgbLedDriver) Halt() (errs []error) { return } +func (l *RgbLedDriver) Halt() (err error) { return } // Name returns the RGBLEDDrivers name func (l *RgbLedDriver) Name() string { return l.name } diff --git a/drivers/gpio/servo_driver.go b/drivers/gpio/servo_driver.go index 149fbedd1..d5d8031b6 100644 --- a/drivers/gpio/servo_driver.go +++ b/drivers/gpio/servo_driver.go @@ -58,10 +58,10 @@ func (s *ServoDriver) Pin() string { return s.pin } func (s *ServoDriver) Connection() gobot.Connection { return s.connection.(gobot.Connection) } // Start implements the Driver interface -func (s *ServoDriver) Start() (errs []error) { return } +func (s *ServoDriver) Start() (err error) { return } // Halt implements the Driver interface -func (s *ServoDriver) Halt() (errs []error) { return } +func (s *ServoDriver) Halt() (err error) { return } // Move sets the servo to the specified angle. Acceptable angles are 0-180 func (s *ServoDriver) Move(angle uint8) (err error) { diff --git a/drivers/i2c/adafruit_driver.go b/drivers/i2c/adafruit_driver.go index d2b24beab..dfb778db3 100644 --- a/drivers/i2c/adafruit_driver.go +++ b/drivers/i2c/adafruit_driver.go @@ -103,14 +103,14 @@ type AdafruitMotorHatDriver struct { // SetMotorHatAddress sets the I2C address for the DC and Stepper Motor HAT. // This addressing flexibility empowers "stacking" the HATs. -func (a *AdafruitMotorHatDriver) SetMotorHatAddress(addr int) (errs []error) { +func (a *AdafruitMotorHatDriver) SetMotorHatAddress(addr int) (err error) { motorHatAddress = addr return } // SetServoHatAddress sets the I2C address for the PWM-Servo Motor HAT. // This addressing flexibility empowers "stacking" the HATs. -func (a *AdafruitMotorHatDriver) SetServoHatAddress(addr int) (errs []error) { +func (a *AdafruitMotorHatDriver) SetServoHatAddress(addr int) (err error) { servoHatAddress = addr return } @@ -157,12 +157,12 @@ func NewAdafruitMotorHatDriver(a I2c) *AdafruitMotorHatDriver { } // Start initializes both I2C-addressable Adafruit Motor HAT drivers -func (a *AdafruitMotorHatDriver) Start() (errs []error) { +func (a *AdafruitMotorHatDriver) Start() (err error) { addrs := []int{motorHatAddress, servoHatAddress} for i := range addrs { if err := a.connection.I2cStart(addrs[i]); err != nil { - return []error{err} + return err } if err := a.setAllPWM(addrs[i], 0, 0); err != nil { return @@ -197,7 +197,7 @@ func (a *AdafruitMotorHatDriver) Start() (errs []error) { } // Halt returns true if devices is halted successfully -func (a *AdafruitMotorHatDriver) Halt() (errs []error) { return } +func (a *AdafruitMotorHatDriver) Halt() (err error) { return } // setPWM sets the start (on) and end (off) of the high-segment of the PWM pulse // on the specific channel (pin). @@ -463,7 +463,7 @@ func (a *AdafruitMotorHatDriver) oneStep(motor int, dir AdafruitDirection, style } // SetStepperMotorSpeed sets the seconds-per-step for the given Stepper Motor. -func (a *AdafruitMotorHatDriver) SetStepperMotorSpeed(stepperMotor int, rpm int) (errs []error) { +func (a *AdafruitMotorHatDriver) SetStepperMotorSpeed(stepperMotor int, rpm int) (err error) { revSteps := a.stepperMotors[stepperMotor].revSteps a.stepperMotors[stepperMotor].secPerStep = 60.0 / float64(revSteps*rpm) a.stepperMotors[stepperMotor].stepCounter = 0 diff --git a/drivers/i2c/blinkm_driver.go b/drivers/i2c/blinkm_driver.go index a0238a2fc..129b3db9a 100644 --- a/drivers/i2c/blinkm_driver.go +++ b/drivers/i2c/blinkm_driver.go @@ -60,18 +60,18 @@ func (b *BlinkMDriver) Connection() gobot.Connection { return b.connection.(gobo // adaptor returns I2C adaptor // Start writes start bytes -func (b *BlinkMDriver) Start() (errs []error) { +func (b *BlinkMDriver) Start() (err error) { if err := b.connection.I2cStart(blinkmAddress); err != nil { - return []error{err} + return err } if err := b.connection.I2cWrite(blinkmAddress, []byte("o")); err != nil { - return []error{err} + return err } return } // Halt returns true if device is halted successfully -func (b *BlinkMDriver) Halt() (errs []error) { return } +func (b *BlinkMDriver) Halt() (err error) { return } // Rgb sets color using r,g,b params func (b *BlinkMDriver) Rgb(red byte, green byte, blue byte) (err error) { diff --git a/drivers/i2c/helpers_test.go b/drivers/i2c/helpers_test.go index a69e44c6c..693afdcf5 100644 --- a/drivers/i2c/helpers_test.go +++ b/drivers/i2c/helpers_test.go @@ -30,10 +30,10 @@ func (t *i2cTestAdaptor) I2cRead(int, int) (data []byte, err error) { func (t *i2cTestAdaptor) I2cWrite(int, []byte) (err error) { return t.i2cWriteImpl() } -func (t *i2cTestAdaptor) Name() string { return t.name } -func (t *i2cTestAdaptor) SetName(n string) { t.name = n } -func (t *i2cTestAdaptor) Connect() (errs []error) { return } -func (t *i2cTestAdaptor) Finalize() (errs []error) { return } +func (t *i2cTestAdaptor) Name() string { return t.name } +func (t *i2cTestAdaptor) SetName(n string) { t.name = n } +func (t *i2cTestAdaptor) Connect() (err error) { return } +func (t *i2cTestAdaptor) Finalize() (err error) { return } func newI2cTestAdaptor() *i2cTestAdaptor { return &i2cTestAdaptor{ diff --git a/drivers/i2c/hmc6352_driver.go b/drivers/i2c/hmc6352_driver.go index a6771221f..1b1f512dc 100644 --- a/drivers/i2c/hmc6352_driver.go +++ b/drivers/i2c/hmc6352_driver.go @@ -24,18 +24,18 @@ func (h *HMC6352Driver) SetName(n string) { h.name = n } func (h *HMC6352Driver) Connection() gobot.Connection { return h.connection.(gobot.Connection) } // Start initialized the hmc6352 -func (h *HMC6352Driver) Start() (errs []error) { +func (h *HMC6352Driver) Start() (err error) { if err := h.connection.I2cStart(hmc6352Address); err != nil { - return []error{err} + return err } if err := h.connection.I2cWrite(hmc6352Address, []byte("A")); err != nil { - return []error{err} + return err } return } // Halt returns true if devices is halted successfully -func (h *HMC6352Driver) Halt() (errs []error) { return } +func (h *HMC6352Driver) Halt() (err error) { return } // Heading returns the current heading func (h *HMC6352Driver) Heading() (heading uint16, err error) { diff --git a/drivers/i2c/jhd1313m1_driver.go b/drivers/i2c/jhd1313m1_driver.go index 704ecf7f4..0b180d304 100644 --- a/drivers/i2c/jhd1313m1_driver.go +++ b/drivers/i2c/jhd1313m1_driver.go @@ -101,49 +101,49 @@ func (h *JHD1313M1Driver) Connection() gobot.Connection { } // Start starts the backlit and the screen and initializes the states. -func (h *JHD1313M1Driver) Start() []error { +func (h *JHD1313M1Driver) Start() error { if err := h.connection.I2cStart(h.lcdAddress); err != nil { - return []error{err} + return err } if err := h.connection.I2cStart(h.rgbAddress); err != nil { - return []error{err} + return err } time.Sleep(50000 * time.Microsecond) payload := []byte{LCD_CMD, LCD_FUNCTIONSET | LCD_2LINE} if err := h.connection.I2cWrite(h.lcdAddress, payload); err != nil { if err := h.connection.I2cWrite(h.lcdAddress, payload); err != nil { - return []error{err} + return err } } time.Sleep(100 * time.Microsecond) if err := h.connection.I2cWrite(h.lcdAddress, []byte{LCD_CMD, LCD_DISPLAYCONTROL | LCD_DISPLAYON}); err != nil { - return []error{err} + return err } time.Sleep(100 * time.Microsecond) if err := h.Clear(); err != nil { - return []error{err} + return err } if err := h.connection.I2cWrite(h.lcdAddress, []byte{LCD_CMD, LCD_ENTRYMODESET | LCD_ENTRYLEFT | LCD_ENTRYSHIFTDECREMENT}); err != nil { - return []error{err} + return err } if err := h.setReg(0, 0); err != nil { - return []error{err} + return err } if err := h.setReg(1, 0); err != nil { - return []error{err} + return err } if err := h.setReg(0x08, 0xAA); err != nil { - return []error{err} + return err } if err := h.SetRGB(255, 255, 255); err != nil { - return []error{err} + return err } return nil @@ -218,7 +218,7 @@ func (h *JHD1313M1Driver) Scroll(leftToRight bool) error { } // Halt is a noop function. -func (h *JHD1313M1Driver) Halt() []error { return nil } +func (h *JHD1313M1Driver) Halt() error { return nil } func (h *JHD1313M1Driver) setReg(command int, data int) error { return h.connection.I2cWrite(h.rgbAddress, []byte{byte(command), byte(data)}) diff --git a/drivers/i2c/lidarlite_driver.go b/drivers/i2c/lidarlite_driver.go index d50e28424..377e820a3 100644 --- a/drivers/i2c/lidarlite_driver.go +++ b/drivers/i2c/lidarlite_driver.go @@ -28,15 +28,15 @@ func (h *LIDARLiteDriver) SetName(n string) { h.name = n } func (h *LIDARLiteDriver) Connection() gobot.Connection { return h.connection.(gobot.Connection) } // Start initialized the LIDAR -func (h *LIDARLiteDriver) Start() (errs []error) { +func (h *LIDARLiteDriver) Start() (err error) { if err := h.connection.I2cStart(lidarliteAddress); err != nil { - return []error{err} + return err } return } // Halt returns true if devices is halted successfully -func (h *LIDARLiteDriver) Halt() (errs []error) { return } +func (h *LIDARLiteDriver) Halt() (err error) { return } // Distance returns the current distance in cm func (h *LIDARLiteDriver) Distance() (distance int, err error) { diff --git a/drivers/i2c/mcp23017_driver.go b/drivers/i2c/mcp23017_driver.go index dec10aec6..d6f018651 100644 --- a/drivers/i2c/mcp23017_driver.go +++ b/drivers/i2c/mcp23017_driver.go @@ -128,18 +128,18 @@ func (m *MCP23017Driver) SetName(n string) { m.name = n } func (m *MCP23017Driver) Connection() gobot.Connection { return m.connection.(gobot.Connection) } // Halt stops the driver. -func (m *MCP23017Driver) Halt() (err []error) { return } +func (m *MCP23017Driver) Halt() (err error) { return } // Start writes the device configuration. -func (m *MCP23017Driver) Start() (errs []error) { +func (m *MCP23017Driver) Start() (errs error) { if err := m.connection.I2cStart(m.mcp23017Address); err != nil { - return []error{err} + return err } // Set IOCON register with MCP23017 configuration. ioconReg := m.getPort("A").IOCON // IOCON address is the same for Port A or B. ioconVal := m.conf.GetUint8Value() if err := m.connection.I2cWrite(m.mcp23017Address, []uint8{ioconReg, ioconVal}); err != nil { - return []error{err} + return err } return } diff --git a/drivers/i2c/mcp23017_driver_test.go b/drivers/i2c/mcp23017_driver_test.go index 87419d516..8685ed6cb 100644 --- a/drivers/i2c/mcp23017_driver_test.go +++ b/drivers/i2c/mcp23017_driver_test.go @@ -26,10 +26,10 @@ func (t *i2cMcpTestAdaptor) I2cRead(address int, numBytes int) (data []byte, err func (t *i2cMcpTestAdaptor) I2cWrite(int, []byte) (err error) { return t.i2cMcpWriteImpl() } -func (t *i2cMcpTestAdaptor) Name() string { return t.name } -func (t *i2cMcpTestAdaptor) SetName(n string) { t.name = n } -func (t *i2cMcpTestAdaptor) Connect() (errs []error) { return } -func (t *i2cMcpTestAdaptor) Finalize() (errs []error) { return } +func (t *i2cMcpTestAdaptor) Name() string { return t.name } +func (t *i2cMcpTestAdaptor) SetName(n string) { t.name = n } +func (t *i2cMcpTestAdaptor) Connect() (err error) { return } +func (t *i2cMcpTestAdaptor) Finalize() (err error) { return } func newMcpI2cTestAdaptor() *i2cMcpTestAdaptor { return &i2cMcpTestAdaptor{ diff --git a/drivers/i2c/mma7660_driver.go b/drivers/i2c/mma7660_driver.go index a3e5ccaec..df8a7d195 100644 --- a/drivers/i2c/mma7660_driver.go +++ b/drivers/i2c/mma7660_driver.go @@ -47,28 +47,28 @@ func (h *MMA7660Driver) SetName(n string) { h.name = n } func (h *MMA7660Driver) Connection() gobot.Connection { return h.connection.(gobot.Connection) } // Start initialized the mma7660 -func (h *MMA7660Driver) Start() (errs []error) { +func (h *MMA7660Driver) Start() (err error) { if err := h.connection.I2cStart(mma7660Address); err != nil { - return []error{err} + return err } if err := h.connection.I2cWrite(mma7660Address, []byte{MMA7660_MODE, MMA7660_STAND_BY}); err != nil { - return []error{err} + return err } if err := h.connection.I2cWrite(mma7660Address, []byte{MMA7660_SR, MMA7660_AUTO_SLEEP_32}); err != nil { - return []error{err} + return err } if err := h.connection.I2cWrite(mma7660Address, []byte{MMA7660_MODE, MMA7660_ACTIVE}); err != nil { - return []error{err} + return err } return } // Halt returns true if devices is halted successfully -func (h *MMA7660Driver) Halt() (errs []error) { return } +func (h *MMA7660Driver) Halt() (err error) { return } // Acceleration returns the acceleration of the provided x, y, z func (h *MMA7660Driver) Acceleration(x, y, z float64) (ax, ay, az float64) { diff --git a/drivers/i2c/mpl115a2_driver.go b/drivers/i2c/mpl115a2_driver.go index 301cc8e7f..ebccfc6e5 100644 --- a/drivers/i2c/mpl115a2_driver.go +++ b/drivers/i2c/mpl115a2_driver.go @@ -61,13 +61,13 @@ func (h *MPL115A2Driver) Connection() gobot.Connection { return h.connection.(go // Start writes initialization bytes and reads from adaptor // using specified interval to accelerometer andtemperature data -func (h *MPL115A2Driver) Start() (errs []error) { +func (h *MPL115A2Driver) Start() (err error) { var temperature uint16 var pressure uint16 var pressureComp float32 if err := h.initialization(); err != nil { - return []error{err} + return err } go func() { @@ -108,7 +108,7 @@ func (h *MPL115A2Driver) Start() (errs []error) { } // Halt returns true if devices is halted successfully -func (h *MPL115A2Driver) Halt() (err []error) { return } +func (h *MPL115A2Driver) Halt() (err error) { return } func (h *MPL115A2Driver) initialization() (err error) { var coA0 int16 diff --git a/drivers/i2c/mpu6050_driver.go b/drivers/i2c/mpu6050_driver.go index 09cab319f..a8386c014 100644 --- a/drivers/i2c/mpu6050_driver.go +++ b/drivers/i2c/mpu6050_driver.go @@ -67,9 +67,9 @@ func (h *MPU6050Driver) Connection() gobot.Connection { return h.connection.(gob // Start writes initialization bytes and reads from adaptor // using specified interval to accelerometer andtemperature data -func (h *MPU6050Driver) Start() (errs []error) { +func (h *MPU6050Driver) Start() (err error) { if err := h.initialize(); err != nil { - return []error{err} + return err } go func() { @@ -96,7 +96,7 @@ func (h *MPU6050Driver) Start() (errs []error) { } // Halt returns true if devices is halted successfully -func (h *MPU6050Driver) Halt() (errs []error) { return } +func (h *MPU6050Driver) Halt() (err error) { return } func (h *MPU6050Driver) initialize() (err error) { if err = h.connection.I2cStart(mpu6050Address); err != nil { diff --git a/drivers/i2c/wiichuck_driver.go b/drivers/i2c/wiichuck_driver.go index 234839113..614b651af 100644 --- a/drivers/i2c/wiichuck_driver.go +++ b/drivers/i2c/wiichuck_driver.go @@ -62,9 +62,9 @@ func (w *WiichuckDriver) Connection() gobot.Connection { return w.connection.(go // Start initilizes i2c and reads from adaptor // using specified interval to update with new value -func (w *WiichuckDriver) Start() (errs []error) { +func (w *WiichuckDriver) Start() (errs error) { if err := w.connection.I2cStart(wiichuckAddress); err != nil { - return []error{err} + return err } go func() { @@ -97,7 +97,7 @@ func (w *WiichuckDriver) Start() (errs []error) { } // Halt returns true if driver is halted successfully -func (w *WiichuckDriver) Halt() (errs []error) { return } +func (w *WiichuckDriver) Halt() (err error) { return } // update parses value to update buttons and joystick. // If value is encrypted, warning message is printed diff --git a/examples/batty.go b/examples/batty.go index 6c2c7fbad..c1e6f9ec7 100644 --- a/examples/batty.go +++ b/examples/batty.go @@ -46,11 +46,11 @@ type loopbackAdaptor struct { port string } -func (t *loopbackAdaptor) Finalize() (errs []error) { return } -func (t *loopbackAdaptor) Connect() (errs []error) { return } -func (t *loopbackAdaptor) Name() string { return t.name } -func (t *loopbackAdaptor) SetName(n string) { t.name = n } -func (t *loopbackAdaptor) Port() string { return t.port } +func (t *loopbackAdaptor) Finalize() (err error) { return } +func (t *loopbackAdaptor) Connect() (err error) { return } +func (t *loopbackAdaptor) Name() string { return t.name } +func (t *loopbackAdaptor) SetName(n string) { t.name = n } +func (t *loopbackAdaptor) Port() string { return t.port } func NewLoopbackAdaptor(port string) *loopbackAdaptor { return &loopbackAdaptor{ @@ -69,8 +69,8 @@ type pingDriver struct { gobot.Commander } -func (t *pingDriver) Start() (errs []error) { return } -func (t *pingDriver) Halt() (errs []error) { return } +func (t *pingDriver) Start() (err error) { return } +func (t *pingDriver) Halt() (err error) { return } func (t *pingDriver) Name() string { return t.name } func (t *pingDriver) SetName(n string) { t.name = n } func (t *pingDriver) Pin() string { return t.pin } diff --git a/helpers_test.go b/helpers_test.go index 59f2023dd..b97cf7c03 100644 --- a/helpers_test.go +++ b/helpers_test.go @@ -23,11 +23,11 @@ type testDriver struct { Commander } -var testDriverStart = func() (errs []error) { return } -var testDriverHalt = func() (errs []error) { return } +var testDriverStart = func() (err error) { return } +var testDriverHalt = func() (err error) { return } -func (t *testDriver) Start() (errs []error) { return testDriverStart() } -func (t *testDriver) Halt() (errs []error) { return testDriverHalt() } +func (t *testDriver) Start() (err error) { return testDriverStart() } +func (t *testDriver) Halt() (err error) { return testDriverHalt() } func (t *testDriver) Name() string { return t.name } func (t *testDriver) SetName(n string) { t.name = n } func (t *testDriver) Pin() string { return t.pin } @@ -51,14 +51,14 @@ type testAdaptor struct { port string } -var testAdaptorConnect = func() (errs []error) { return } -var testAdaptorFinalize = func() (errs []error) { return } +var testAdaptorConnect = func() (err error) { return } +var testAdaptorFinalize = func() (err error) { return } -func (t *testAdaptor) Finalize() (errs []error) { return testAdaptorFinalize() } -func (t *testAdaptor) Connect() (errs []error) { return testAdaptorConnect() } -func (t *testAdaptor) Name() string { return t.name } -func (t *testAdaptor) SetName(n string) { t.name = n } -func (t *testAdaptor) Port() string { return t.port } +func (t *testAdaptor) Finalize() (err error) { return testAdaptorFinalize() } +func (t *testAdaptor) Connect() (err error) { return testAdaptorConnect() } +func (t *testAdaptor) Name() string { return t.name } +func (t *testAdaptor) SetName(n string) { t.name = n } +func (t *testAdaptor) Port() string { return t.port } func newTestAdaptor(name string, port string) *testAdaptor { return &testAdaptor{ diff --git a/master.go b/master.go index 6752a817a..f12440bfa 100644 --- a/master.go +++ b/master.go @@ -1,9 +1,10 @@ package gobot import ( - "log" "os" "os/signal" + + multierror "github.com/hashicorp/go-multierror" ) // JSONMaster is a JSON representation of a Gobot Master. @@ -55,19 +56,16 @@ 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() (errs []error) { - if rerrs := g.robots.Start(!g.AutoRun); len(rerrs) > 0 { - for _, err := range rerrs { - log.Println("Error:", err) - errs = append(errs, err) - } +func (g *Master) Start() (err error) { + if rerr := g.robots.Start(!g.AutoRun); rerr != nil { + err = multierror.Append(err, rerr) return } if g.AutoRun { c := make(chan os.Signal, 1) g.trap(c) - if len(errs) > 0 { + if err != nil { // there was an error during start, so we immediately pass the interrupt // in order to disconnect the initialized robots, connections and devices c <- os.Interrupt @@ -80,19 +78,16 @@ func (g *Master) Start() (errs []error) { g.Stop() } - return errs + return err } // Stop calls the Stop method on each robot in its collection of robots. -func (g *Master) Stop() (errs []error) { - if rerrs := g.robots.Stop(); len(rerrs) > 0 { - for _, err := range rerrs { - log.Println("Error:", err) - errs = append(errs, err) - } +func (g *Master) Stop() (err error) { + if rerr := g.robots.Stop(); rerr != nil { + err = multierror.Append(err, rerr) } - return errs + return } // Robots returns all robots associated with this Gobot Master. diff --git a/master_test.go b/master_test.go index 33da661ba..5127f7d37 100644 --- a/master_test.go +++ b/master_test.go @@ -80,55 +80,47 @@ func TestGobotToJSON(t *testing.T) { func TestMasterStart(t *testing.T) { g := initTestMaster() - gobottest.Assert(t, len(g.Start()), 0) - gobottest.Assert(t, len(g.Stop()), 0) + gobottest.Assert(t, g.Start(), nil) + gobottest.Assert(t, g.Stop(), nil) } func TestMasterStartDriverErrors(t *testing.T) { g := initTestMaster1Robot() - testDriverStart = func() (errs []error) { - return []error{ - errors.New("driver start error 1"), - } + testDriverStart = func() (err error) { + return errors.New("driver start error 1") } - gobottest.Assert(t, len(g.Start()), 1) - gobottest.Assert(t, len(g.Stop()), 0) + gobottest.Assert(t, g.Start().Error(), "3 error(s) occurred:\n\n* driver start error 1\n* driver start error 1\n* driver start error 1") + gobottest.Assert(t, g.Stop(), nil) - testDriverStart = func() (errs []error) { return } + testDriverStart = func() (err error) { return } } func TestMasterStartAdaptorErrors(t *testing.T) { g := initTestMaster1Robot() - testAdaptorConnect = func() (errs []error) { - return []error{ - errors.New("adaptor start error 1"), - } + testAdaptorConnect = func() (err error) { + return errors.New("adaptor start error 1") } - gobottest.Assert(t, len(g.Start()), 1) - gobottest.Assert(t, len(g.Stop()), 0) + gobottest.Assert(t, g.Start().Error(), "3 error(s) occurred:\n\n* adaptor start error 1\n* adaptor start error 1\n* adaptor start error 1") + gobottest.Assert(t, g.Stop(), nil) - testAdaptorConnect = func() (errs []error) { return } + testAdaptorConnect = func() (err error) { return } } func TestMasterHaltErrors(t *testing.T) { g := initTestMaster1Robot() - testDriverHalt = func() (errs []error) { - return []error{ - errors.New("driver halt error 1"), - } + testDriverHalt = func() (err error) { + return errors.New("driver halt error 2") } - testAdaptorFinalize = func() (errs []error) { - return []error{ - errors.New("adaptor finalize error 1"), - } + testAdaptorFinalize = func() (err error) { + return errors.New("adaptor finalize error 2") } - gobottest.Assert(t, len(g.Start()), 0) - gobottest.Assert(t, len(g.Stop()), 6) + gobottest.Assert(t, g.Start(), nil) + gobottest.Assert(t, g.Stop().Error(), "3 error(s) occurred:\n\n* adaptor finalize error 2\n* adaptor finalize error 2\n* adaptor finalize error 2") } diff --git a/platforms/neurosky/neurosky_driver.go b/platforms/neurosky/neurosky_driver.go index 315c2f32f..864ce612b 100644 --- a/platforms/neurosky/neurosky_driver.go +++ b/platforms/neurosky/neurosky_driver.go @@ -85,7 +85,7 @@ func (n *Driver) adaptor() *Adaptor { // Start creates a go routine to listen from serial port // and parse buffer readings -func (n *Driver) Start() (errs []error) { +func (n *Driver) Start() (err error) { go func() { for { buff := make([]byte, 1024) @@ -101,7 +101,7 @@ func (n *Driver) Start() (errs []error) { } // Halt stops neurosky driver (void) -func (n *Driver) Halt() (errs []error) { return } +func (n *Driver) Halt() (err error) { return } // parse converts bytes buffer into packets until no more data is present func (n *Driver) parse(buf *bytes.Buffer) { diff --git a/platforms/opencv/camera_driver.go b/platforms/opencv/camera_driver.go index d5383c293..61952f054 100644 --- a/platforms/opencv/camera_driver.go +++ b/platforms/opencv/camera_driver.go @@ -64,9 +64,9 @@ func (c *CameraDriver) Connection() gobot.Connection { return nil } // Start initializes camera by grabbing a frame // every `interval` and publishing an frame event -func (c *CameraDriver) Start() (errs []error) { +func (c *CameraDriver) Start() (err error) { if err := c.start(c); err != nil { - return []error{err} + return err } go func() { for { @@ -76,11 +76,11 @@ func (c *CameraDriver) Start() (errs []error) { c.Publish(Frame, image) } } - <-time.After(c.interval) + time.Sleep(c.interval) } }() return } // Halt stops camera driver -func (c *CameraDriver) Halt() (errs []error) { return } +func (c *CameraDriver) Halt() (err error) { return } diff --git a/platforms/particle/adaptor.go b/platforms/particle/adaptor.go index 0d0ae75f0..ef19cce8c 100644 --- a/platforms/particle/adaptor.go +++ b/platforms/particle/adaptor.go @@ -51,12 +51,12 @@ 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() (errs []error) { +func (s *Adaptor) Connect() (err error) { return } // Finalize returns true if connection to Particle Photon or Electron is finalized successfully -func (s *Adaptor) Finalize() (errs []error) { +func (s *Adaptor) Finalize() (err error) { return } diff --git a/platforms/pebble/pebble_driver.go b/platforms/pebble/pebble_driver.go index 325053273..9daa2b5e5 100644 --- a/platforms/pebble/pebble_driver.go +++ b/platforms/pebble/pebble_driver.go @@ -55,10 +55,10 @@ func (d *Driver) SetName(n string) { d.name = n } func (d *Driver) Connection() gobot.Connection { return d.connection } // Start returns true if driver is initialized correctly -func (d *Driver) Start() (errs []error) { return } +func (d *Driver) Start() (err error) { return } // Halt returns true if driver is halted successfully -func (d *Driver) Halt() (errs []error) { return } +func (d *Driver) Halt() (err error) { return } // PublishEvent publishes event with specified name and data in gobot func (d *Driver) PublishEvent(name string, data string) { diff --git a/platforms/raspi/raspi_adaptor.go b/platforms/raspi/raspi_adaptor.go index 3c0e15283..91b3266e5 100644 --- a/platforms/raspi/raspi_adaptor.go +++ b/platforms/raspi/raspi_adaptor.go @@ -8,6 +8,7 @@ import ( "strconv" "strings" + multierror "github.com/hashicorp/go-multierror" "github.com/hybridgroup/gobot" "github.com/hybridgroup/gobot/sysfs" ) @@ -144,30 +145,30 @@ func (r *Adaptor) SetName(n string) { r.name = n } // Connect starts connection with board and creates // digitalPins and pwmPins adaptor maps -func (r *Adaptor) Connect() (errs []error) { +func (r *Adaptor) Connect() (err error) { return } // Finalize closes connection to board and pins -func (r *Adaptor) Finalize() (errs []error) { +func (r *Adaptor) Finalize() (err error) { for _, pin := range r.digitalPins { if pin != nil { - if err := pin.Unexport(); err != nil { - errs = append(errs, err) + if perr := pin.Unexport(); err != nil { + err = multierror.Append(err, perr) } } } for _, pin := range r.pwmPins { - if err := r.piBlaster(fmt.Sprintf("release %v\n", pin)); err != nil { - errs = append(errs, err) + if perr := r.piBlaster(fmt.Sprintf("release %v\n", pin)); err != nil { + err = multierror.Append(err, perr) } } if r.i2cDevice != nil { - if err := r.i2cDevice.Close(); err != nil { - errs = append(errs, err) + if perr := r.i2cDevice.Close(); err != nil { + err = multierror.Append(err, perr) } } - return errs + return err } func (r *Adaptor) translatePin(pin string) (i int, err error) { diff --git a/platforms/sphero/sphero_driver.go b/platforms/sphero/sphero_driver.go index d3fbecf12..d9a2df2a7 100644 --- a/platforms/sphero/sphero_driver.go +++ b/platforms/sphero/sphero_driver.go @@ -157,7 +157,7 @@ func (s *SpheroDriver) adaptor() *Adaptor { // Collision sphero.CollisionPacket - On Collision Detected // SensorData sphero.DataStreamingPacket - On Data Streaming event // Error error- On error while processing asynchronous response -func (s *SpheroDriver) Start() (errs []error) { +func (s *SpheroDriver) Start() (err error) { go func() { for { packet := <-s.packetChannel @@ -218,7 +218,7 @@ func (s *SpheroDriver) Start() (errs []error) { // Halt halts the SpheroDriver and sends a SpheroDriver.Stop command to the Sphero. // Returns true on successful halt. -func (s *SpheroDriver) Halt() (errs []error) { +func (s *SpheroDriver) Halt() (err error) { if s.adaptor().connected { gobot.Every(10*time.Millisecond, func() { s.Stop() diff --git a/robot.go b/robot.go index 2d091ded6..e96503af4 100644 --- a/robot.go +++ b/robot.go @@ -5,6 +5,8 @@ import ( "log" "os" "os/signal" + + multierror "github.com/hashicorp/go-multierror" ) // JSONRobot a JSON representation of a Robot. @@ -60,16 +62,14 @@ func (r *Robots) Len() int { } // Start calls the Start method of each Robot in the collection -func (r *Robots) Start(args ...interface{}) (errs []error) { +func (r *Robots) Start(args ...interface{}) (err error) { autoRun := true if args[0] != nil { autoRun = args[0].(bool) } for _, robot := range *r { - if errs = robot.Start(autoRun); len(errs) > 0 { - for i, err := range errs { - errs[i] = fmt.Errorf("Robot %q: %v", robot.Name, err) - } + if rerr := robot.Start(autoRun); rerr != nil { + err = multierror.Append(err, rerr) return } } @@ -77,12 +77,10 @@ func (r *Robots) Start(args ...interface{}) (errs []error) { } // Stop calls the Stop method of each Robot in the collection -func (r *Robots) Stop() (errs []error) { +func (r *Robots) Stop() (err error) { for _, robot := range *r { - if errs = robot.Stop(); len(errs) > 0 { - for i, err := range errs { - errs[i] = fmt.Errorf("Robot %q: %v", robot.Name, err) - } + if rerr := robot.Stop(); rerr != nil { + err = multierror.Append(err, rerr) return } } @@ -144,17 +142,17 @@ func NewRobot(v ...interface{}) *Robot { } // Start a Robot's Connections, Devices, and work. -func (r *Robot) Start(args ...interface{}) (errs []error) { +func (r *Robot) Start(args ...interface{}) (err error) { if len(args) > 0 && args[0] != nil { r.AutoRun = args[0].(bool) } log.Println("Starting Robot", r.Name, "...") - if cerrs := r.Connections().Start(); len(cerrs) > 0 { - errs = append(errs, cerrs...) + if cerr := r.Connections().Start(); cerr != nil { + err = multierror.Append(err, cerr) return } - if derrs := r.Devices().Start(); len(derrs) > 0 { - errs = append(errs, derrs...) + if derr := r.Devices().Start(); derr != nil { + err = multierror.Append(err, derr) return } if r.Work == nil { @@ -170,7 +168,7 @@ func (r *Robot) Start(args ...interface{}) (errs []error) { if r.AutoRun { c := make(chan os.Signal, 1) r.trap(c) - if len(errs) > 0 { + if err != nil { // there was an error during start, so we immediately pass the interrupt // in order to disconnect the initialized robots, connections and devices c <- os.Interrupt @@ -187,12 +185,12 @@ func (r *Robot) Start(args ...interface{}) (errs []error) { } // Stop stops a Robot's connections and Devices -func (r *Robot) Stop() (errs []error) { +func (r *Robot) Stop() (err error) { log.Println("Stopping Robot", r.Name, "...") - errs = append(errs, r.Devices().Halt()...) - errs = append(errs, r.Connections().Finalize()...) + err = r.Devices().Halt() + err = r.Connections().Finalize() r.done <- true - return errs + return err } // Devices returns all devices associated with this Robot.