1
0
mirror of https://github.com/hybridgroup/gobot.git synced 2025-05-11 19:29:20 +08:00

Merge branch 'erkkah-better-i2c' into dev

This commit is contained in:
deadprogram 2017-02-08 12:00:50 +01:00
commit 9da8e3fd19
46 changed files with 1418 additions and 913 deletions

View File

@ -94,8 +94,10 @@ type adaFruitStepperMotor struct {
// with full PWM speed control. It has a dedicated PWM driver chip onboard to
// control both motor direction and speed over I2C.
type AdafruitMotorHatDriver struct {
name string
connection I2c
name string
connector I2cConnector
motorHatConnection I2cConnection
servoHatConnection I2cConnection
gobot.Commander
dcMotors []adaFruitDCMotor
stepperMotors []adaFruitStepperMotor
@ -122,11 +124,11 @@ func (a *AdafruitMotorHatDriver) Name() string { return a.name }
func (a *AdafruitMotorHatDriver) SetName(n string) { a.name = n }
// Connection identifies the particular adapter object
func (a *AdafruitMotorHatDriver) Connection() gobot.Connection { return a.connection.(gobot.Connection) }
func (a *AdafruitMotorHatDriver) Connection() gobot.Connection { return a.connector.(gobot.Connection) }
// NewAdafruitMotorHatDriver initializes the internal DCMotor and StepperMotor types.
// Again the Adafruit Motor Hat supports up to four DC motors and up to two stepper motors.
func NewAdafruitMotorHatDriver(a I2c) *AdafruitMotorHatDriver {
func NewAdafruitMotorHatDriver(conn I2cConnector) *AdafruitMotorHatDriver {
var dc []adaFruitDCMotor
var st []adaFruitStepperMotor
for i := 0; i < 4; i++ {
@ -145,9 +147,10 @@ func NewAdafruitMotorHatDriver(a I2c) *AdafruitMotorHatDriver {
dc = append(dc, adaFruitDCMotor{pwmPin: 7, in1Pin: 5, in2Pin: 6})
}
}
driver := &AdafruitMotorHatDriver{
name: gobot.DefaultName("AdafruitMotorHat"),
connection: a,
connector: conn,
Commander: gobot.NewCommander(),
dcMotors: dc,
stepperMotors: st,
@ -156,43 +159,60 @@ func NewAdafruitMotorHatDriver(a I2c) *AdafruitMotorHatDriver {
return driver
}
// Start initializes both I2C-addressable Adafruit Motor HAT drivers
func (a *AdafruitMotorHatDriver) Start() (err error) {
addrs := []int{motorHatAddress, servoHatAddress}
for i := range addrs {
func (a *AdafruitMotorHatDriver) startDriver(connection I2cConnection) (err error) {
if err = a.setAllPWM(connection, 0, 0); err != nil {
return
}
reg := byte(_Mode2)
val := byte(_Outdrv)
if _, err = connection.Write([]byte{reg, val}); err != nil {
return
}
reg = byte(_Mode1)
val = byte(_AllCall)
if _, err = connection.Write([]byte{reg, val}); err != nil {
return
}
time.Sleep(5 * time.Millisecond)
if err = a.connection.I2cStart(addrs[i]); err != nil {
return
}
if err = a.setAllPWM(addrs[i], 0, 0); err != nil {
return
}
reg := byte(_Mode2)
val := byte(_Outdrv)
if err = a.connection.I2cWrite(addrs[i], []byte{reg, val}); err != nil {
return
}
// Read a byte from the I2C device. Note: no ability to read from a specified reg?
mode1 := []byte{0}
_, rerr := connection.Read(mode1)
if rerr != nil {
return rerr
}
if len(mode1) > 0 {
reg = byte(_Mode1)
val = byte(_AllCall)
if err = a.connection.I2cWrite(addrs[i], []byte{reg, val}); err != nil {
val = mode1[0] & _Sleep
if _, err = connection.Write([]byte{reg, val}); err != nil {
return
}
time.Sleep(5 * time.Millisecond)
// Read a byte from the I2C device. Note: no ability to read from a specified reg?
mode1, rerr := a.connection.I2cRead(addrs[i], 1)
if rerr != nil {
return rerr
}
if len(mode1) > 0 {
reg = byte(_Mode1)
val = mode1[0] & _Sleep
if err = a.connection.I2cWrite(addrs[i], []byte{reg, val}); err != nil {
return
}
time.Sleep(5 * time.Millisecond)
}
}
return
}
// Start initializes both I2C-addressable Adafruit Motor HAT drivers
func (a *AdafruitMotorHatDriver) Start() (err error) {
bus := a.connector.I2cGetDefaultBus()
if a.servoHatConnection, err = a.connector.I2cGetConnection(servoHatAddress, bus); err != nil {
return
}
if err = a.startDriver(a.servoHatConnection); err != nil {
return
}
if a.motorHatConnection, err = a.connector.I2cGetConnection(motorHatAddress, bus); err != nil {
return
}
if err = a.startDriver(a.motorHatConnection); err != nil {
return
}
return
}
@ -201,7 +221,7 @@ 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).
func (a *AdafruitMotorHatDriver) setPWM(i2cAddr int, pin byte, on, off int32) (err error) {
func (a *AdafruitMotorHatDriver) setPWM(conn I2cConnection, pin byte, on, off int32) (err error) {
// register and values to be written to that register
regVals := make(map[int][]byte)
regVals[0] = []byte{byte(_LedZeroOnL + 4*pin), byte(on & 0xff)}
@ -209,7 +229,7 @@ func (a *AdafruitMotorHatDriver) setPWM(i2cAddr int, pin byte, on, off int32) (e
regVals[2] = []byte{byte(_LedZeroOffL + 4*pin), byte(off & 0xff)}
regVals[3] = []byte{byte(_LedZeroOffH + 4*pin), byte(off >> 8)}
for i := 0; i < len(regVals); i++ {
if err = a.connection.I2cWrite(i2cAddr, regVals[i]); err != nil {
if _, err = conn.Write(regVals[i]); err != nil {
return
}
}
@ -218,7 +238,7 @@ func (a *AdafruitMotorHatDriver) setPWM(i2cAddr int, pin byte, on, off int32) (e
// SetServoMotorFreq sets the frequency for the currently addressed PWM Servo HAT.
func (a *AdafruitMotorHatDriver) SetServoMotorFreq(freq float64) (err error) {
if err = a.setPWMFreq(servoHatAddress, freq); err != nil {
if err = a.setPWMFreq(a.servoHatConnection, freq); err != nil {
return
}
return
@ -227,7 +247,7 @@ func (a *AdafruitMotorHatDriver) SetServoMotorFreq(freq float64) (err error) {
// SetServoMotorPulse is a convenience function to specify the 'tick' value,
// between 0-4095, when the signal will turn on, and when it will turn off.
func (a *AdafruitMotorHatDriver) SetServoMotorPulse(channel byte, on, off int32) (err error) {
if err = a.setPWM(servoHatAddress, channel, on, off); err != nil {
if err = a.setPWM(a.servoHatConnection, channel, on, off); err != nil {
return
}
return
@ -237,7 +257,7 @@ func (a *AdafruitMotorHatDriver) SetServoMotorPulse(channel byte, on, off int32)
// pulses per second are generated by the integrated circuit. The frequency
// determines how "long" each pulse is in duration from start to finish,
// taking into account the high and low segments of the pulse.
func (a *AdafruitMotorHatDriver) setPWMFreq(i2cAddr int, freq float64) (err error) {
func (a *AdafruitMotorHatDriver) setPWMFreq(conn I2cConnection, freq float64) (err error) {
// 25MHz
preScaleVal := 25000000.0
// 12-bit
@ -251,7 +271,8 @@ func (a *AdafruitMotorHatDriver) setPWMFreq(i2cAddr int, freq float64) (err erro
log.Printf("Final pre-scale: %.2f", preScale)
}
// default (and only) reads register 0
oldMode, err := a.connection.I2cRead(i2cAddr, 1)
oldMode := []byte{0}
_, err = conn.Read(oldMode)
if err != nil {
return
}
@ -259,20 +280,20 @@ func (a *AdafruitMotorHatDriver) setPWMFreq(i2cAddr int, freq float64) (err erro
if len(oldMode) > 0 {
newMode := (oldMode[0] & 0x7F) | 0x10
reg := byte(_Mode1)
if err = a.connection.I2cWrite(i2cAddr, []byte{reg, newMode}); err != nil {
if _, err = conn.Write([]byte{reg, newMode}); err != nil {
return
}
reg = byte(_Prescale)
val := byte(math.Floor(preScale))
if err = a.connection.I2cWrite(i2cAddr, []byte{reg, val}); err != nil {
if _, err = conn.Write([]byte{reg, val}); err != nil {
return
}
reg = byte(_Mode1)
if err = a.connection.I2cWrite(i2cAddr, []byte{reg, oldMode[0]}); err != nil {
if _, err = conn.Write([]byte{reg, oldMode[0]}); err != nil {
return
}
time.Sleep(5 * time.Millisecond)
if err = a.connection.I2cWrite(i2cAddr, []byte{reg, (oldMode[0] | 0x80)}); err != nil {
if _, err = conn.Write([]byte{reg, (oldMode[0] | 0x80)}); err != nil {
return
}
}
@ -280,7 +301,7 @@ func (a *AdafruitMotorHatDriver) setPWMFreq(i2cAddr int, freq float64) (err erro
}
// setAllPWM sets all PWM channels for the given address
func (a *AdafruitMotorHatDriver) setAllPWM(addr int, on, off int32) (err error) {
func (a *AdafruitMotorHatDriver) setAllPWM(conn I2cConnection, on, off int32) (err error) {
// register and values to be written to that register
regVals := make(map[int][]byte)
regVals[0] = []byte{byte(_AllLedOnL), byte(on & 0xff)}
@ -288,18 +309,19 @@ func (a *AdafruitMotorHatDriver) setAllPWM(addr int, on, off int32) (err error)
regVals[2] = []byte{byte(_AllLedOffL), byte(off & 0xFF)}
regVals[3] = []byte{byte(_AllLedOffH), byte(off >> 8)}
for i := 0; i < len(regVals); i++ {
if err = a.connection.I2cWrite(addr, regVals[i]); err != nil {
if _, err = conn.Write(regVals[i]); err != nil {
return
}
}
return
}
func (a *AdafruitMotorHatDriver) setPin(i2cAddr int, pin byte, value int32) (err error) {
func (a *AdafruitMotorHatDriver) setPin(conn I2cConnection, pin byte, value int32) (err error) {
if value == 0 {
return a.setPWM(i2cAddr, pin, 0, 4096)
return a.setPWM(conn, pin, 0, 4096)
}
if value == 1 {
return a.setPWM(i2cAddr, pin, 4096, 0)
return a.setPWM(conn, pin, 4096, 0)
}
return nil
}
@ -307,7 +329,7 @@ func (a *AdafruitMotorHatDriver) setPin(i2cAddr int, pin byte, value int32) (err
// SetDCMotorSpeed will set the appropriate pins to run the specified DC motor
// for the given speed.
func (a *AdafruitMotorHatDriver) SetDCMotorSpeed(dcMotor int, speed int32) (err error) {
if err = a.setPWM(motorHatAddress, a.dcMotors[dcMotor].pwmPin, 0, speed*16); err != nil {
if err = a.setPWM(a.motorHatConnection, a.dcMotors[dcMotor].pwmPin, 0, speed*16); err != nil {
return
}
return
@ -319,29 +341,30 @@ func (a *AdafruitMotorHatDriver) RunDCMotor(dcMotor int, dir AdafruitDirection)
switch {
case dir == AdafruitForward:
if err = a.setPin(motorHatAddress, a.dcMotors[dcMotor].in2Pin, 0); err != nil {
if err = a.setPin(a.motorHatConnection, a.dcMotors[dcMotor].in2Pin, 0); err != nil {
return
}
if err = a.setPin(motorHatAddress, a.dcMotors[dcMotor].in1Pin, 1); err != nil {
if err = a.setPin(a.motorHatConnection, a.dcMotors[dcMotor].in1Pin, 1); err != nil {
return
}
case dir == AdafruitBackward:
if err = a.setPin(motorHatAddress, a.dcMotors[dcMotor].in1Pin, 0); err != nil {
if err = a.setPin(a.motorHatConnection, a.dcMotors[dcMotor].in1Pin, 0); err != nil {
return
}
if err = a.setPin(motorHatAddress, a.dcMotors[dcMotor].in2Pin, 1); err != nil {
if err = a.setPin(a.motorHatConnection, a.dcMotors[dcMotor].in2Pin, 1); err != nil {
return
}
case dir == AdafruitRelease:
if err = a.setPin(motorHatAddress, a.dcMotors[dcMotor].in1Pin, 0); err != nil {
if err = a.setPin(a.motorHatConnection, a.dcMotors[dcMotor].in1Pin, 0); err != nil {
return
}
if err = a.setPin(motorHatAddress, a.dcMotors[dcMotor].in2Pin, 0); err != nil {
if err = a.setPin(a.motorHatConnection, a.dcMotors[dcMotor].in2Pin, 0); err != nil {
return
}
}
return
}
func (a *AdafruitMotorHatDriver) oneStep(motor int, dir AdafruitDirection, style AdafruitStepStyle) (steps int, err error) {
pwmA := 255
pwmB := 255
@ -419,10 +442,10 @@ func (a *AdafruitMotorHatDriver) oneStep(motor int, dir AdafruitDirection, style
a.stepperMotors[motor].currentStep %= stepperMicrosteps * 4
//only really used for microstepping, otherwise always on!
if err = a.setPWM(motorHatAddress, a.stepperMotors[motor].pwmPinA, 0, int32(pwmA*16)); err != nil {
if err = a.setPWM(a.motorHatConnection, a.stepperMotors[motor].pwmPinA, 0, int32(pwmA*16)); err != nil {
return
}
if err = a.setPWM(motorHatAddress, a.stepperMotors[motor].pwmPinB, 0, int32(pwmB*16)); err != nil {
if err = a.setPWM(a.motorHatConnection, a.stepperMotors[motor].pwmPinB, 0, int32(pwmB*16)); err != nil {
return
}
var coils []int32
@ -447,16 +470,16 @@ func (a *AdafruitMotorHatDriver) oneStep(motor int, dir AdafruitDirection, style
currStep, (currStep / (stepperMicrosteps / 2)))
log.Printf("[adafruit_driver] coils state = %v", coils)
}
if err = a.setPin(motorHatAddress, a.stepperMotors[motor].ain2, coils[0]); err != nil {
if err = a.setPin(a.motorHatConnection, a.stepperMotors[motor].ain2, coils[0]); err != nil {
return
}
if err = a.setPin(motorHatAddress, a.stepperMotors[motor].bin1, coils[1]); err != nil {
if err = a.setPin(a.motorHatConnection, a.stepperMotors[motor].bin1, coils[1]); err != nil {
return
}
if err = a.setPin(motorHatAddress, a.stepperMotors[motor].ain1, coils[2]); err != nil {
if err = a.setPin(a.motorHatConnection, a.stepperMotors[motor].ain1, coils[2]); err != nil {
return
}
if err = a.setPin(motorHatAddress, a.stepperMotors[motor].bin2, coils[3]); err != nil {
if err = a.setPin(a.motorHatConnection, a.stepperMotors[motor].bin2, coils[3]); err != nil {
return
}
return a.stepperMotors[motor].currentStep, nil

View File

@ -1,7 +1,6 @@
package i2c
import (
"errors"
"strings"
"testing"
@ -36,16 +35,9 @@ func TestNewAdafruitMotorHatDriver(t *testing.T) {
// Methods
func TestAdafruitMotorHatDriverStart(t *testing.T) {
ada, adaptor := initTestAdafruitMotorHatDriverWithStubbedAdaptor()
ada, _ := initTestAdafruitMotorHatDriverWithStubbedAdaptor()
gobottest.Assert(t, ada.Start(), nil)
adaptor.i2cStartImpl = func() error {
return errors.New("start error")
}
err := ada.Start()
gobottest.Assert(t, err, errors.New("start error"))
}
func TestAdafruitMotorHatDriverHalt(t *testing.T) {
@ -53,6 +45,7 @@ func TestAdafruitMotorHatDriverHalt(t *testing.T) {
gobottest.Assert(t, ada.Halt(), nil)
}
func TestSetHatAddresses(t *testing.T) {
ada, _ := initTestAdafruitMotorHatDriverWithStubbedAdaptor()
@ -65,6 +58,8 @@ func TestSetHatAddresses(t *testing.T) {
func TestAdafruitMotorHatDriverSetServoMotorFreq(t *testing.T) {
ada, _ := initTestAdafruitMotorHatDriverWithStubbedAdaptor()
gobottest.Assert(t, ada.Start(), nil)
freq := 60.0
err := ada.SetServoMotorFreq(freq)
gobottest.Assert(t, err, nil)
@ -73,6 +68,8 @@ func TestAdafruitMotorHatDriverSetServoMotorFreq(t *testing.T) {
func TestAdafruitMotorHatDriverSetServoMotorPulse(t *testing.T) {
ada, _ := initTestAdafruitMotorHatDriverWithStubbedAdaptor()
gobottest.Assert(t, ada.Start(), nil)
var channel byte = 7
var on int32 = 1234
var off int32 = 4321
@ -83,6 +80,8 @@ func TestAdafruitMotorHatDriverSetServoMotorPulse(t *testing.T) {
func TestAdafruitMotorHatDriverSetDCMotorSpeed(t *testing.T) {
ada, _ := initTestAdafruitMotorHatDriverWithStubbedAdaptor()
gobottest.Assert(t, ada.Start(), nil)
dcMotor := 1
var speed int32 = 255
err := ada.SetDCMotorSpeed(dcMotor, speed)
@ -92,6 +91,8 @@ func TestAdafruitMotorHatDriverSetDCMotorSpeed(t *testing.T) {
func TestAdafruitMotorHatDriverRunDCMotor(t *testing.T) {
ada, _ := initTestAdafruitMotorHatDriverWithStubbedAdaptor()
gobottest.Assert(t, ada.Start(), nil)
dcMotor := 1
// NOTE: not using the direction constant to prevent importing
// the i2c package
@ -102,6 +103,8 @@ func TestAdafruitMotorHatDriverRunDCMotor(t *testing.T) {
func TestAdafruitMotorHatDriverSetStepperMotorSpeed(t *testing.T) {
ada, _ := initTestAdafruitMotorHatDriverWithStubbedAdaptor()
gobottest.Assert(t, ada.Start(), nil)
stepperMotor := 1
rpm := 30
gobottest.Assert(t, ada.SetStepperMotorSpeed(stepperMotor, rpm), nil)
@ -110,6 +113,8 @@ func TestAdafruitMotorHatDriverSetStepperMotorSpeed(t *testing.T) {
func TestAdafruitMotorHatDriverStepperStep(t *testing.T) {
ada, _ := initTestAdafruitMotorHatDriverWithStubbedAdaptor()
gobottest.Assert(t, ada.Start(), nil)
// NOTE: not using the direction and style constants to prevent importing
// the i2c package
stepperMotor := 0

View File

@ -11,7 +11,8 @@ const blinkmAddress = 0x09
// BlinkMDriver is a Gobot Driver for a BlinkM LED
type BlinkMDriver struct {
name string
connection I2c
connector I2cConnector
connection I2cConnection
gobot.Commander
}
@ -22,11 +23,11 @@ type BlinkMDriver struct {
// Fade - fades the RGB color
// FirmwareVersion - returns the version of the current Frimware
// Color - returns the color of the LED.
func NewBlinkMDriver(a I2c) *BlinkMDriver {
func NewBlinkMDriver(a I2cConnector) *BlinkMDriver {
b := &BlinkMDriver{
name: gobot.DefaultName("BlinkM"),
connection: a,
Commander: gobot.NewCommander(),
name: gobot.DefaultName("BlinkM"),
Commander: gobot.NewCommander(),
connector: a,
}
b.AddCommand("Rgb", func(params map[string]interface{}) interface{} {
@ -64,10 +65,13 @@ func (b *BlinkMDriver) Connection() gobot.Connection { return b.connection.(gobo
// Start starts the Driver up, and writes start command
func (b *BlinkMDriver) Start() (err error) {
if err := b.connection.I2cStart(blinkmAddress); err != nil {
return err
bus := b.connector.I2cGetDefaultBus()
b.connection, err = b.connector.I2cGetConnection(blinkmAddress, bus)
if err != nil {
return
}
if err := b.connection.I2cWrite(blinkmAddress, []byte("o")); err != nil {
if _, err := b.connection.Write([]byte("o")); err != nil {
return err
}
return
@ -78,29 +82,30 @@ 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) {
if err = b.connection.I2cWrite(blinkmAddress, []byte("n")); err != nil {
if _, err = b.connection.Write([]byte("n")); err != nil {
return
}
err = b.connection.I2cWrite(blinkmAddress, []byte{red, green, blue})
_, err = b.connection.Write([]byte{red, green, blue})
return
}
// Fade removes color using r,g,b params
func (b *BlinkMDriver) Fade(red byte, green byte, blue byte) (err error) {
if err = b.connection.I2cWrite(blinkmAddress, []byte("c")); err != nil {
if _, err = b.connection.Write([]byte("c")); err != nil {
return
}
err = b.connection.I2cWrite(blinkmAddress, []byte{red, green, blue})
_, err = b.connection.Write([]byte{red, green, blue})
return
}
// FirmwareVersion returns version with MAYOR.minor format
func (b *BlinkMDriver) FirmwareVersion() (version string, err error) {
if err = b.connection.I2cWrite(blinkmAddress, []byte("Z")); err != nil {
if _, err = b.connection.Write([]byte("Z")); err != nil {
return
}
data, err := b.connection.I2cRead(blinkmAddress, 2)
if len(data) != 2 || err != nil {
data := []byte{0, 0}
read, err := b.connection.Read(data)
if read != 2 || err != nil {
return
}
return fmt.Sprintf("%v.%v", data[0], data[1]), nil
@ -108,11 +113,12 @@ func (b *BlinkMDriver) FirmwareVersion() (version string, err error) {
// Color returns an array with current rgb color
func (b *BlinkMDriver) Color() (color []byte, err error) {
if err = b.connection.I2cWrite(blinkmAddress, []byte("g")); err != nil {
if _, err = b.connection.Write([]byte("g")); err != nil {
return
}
data, err := b.connection.I2cRead(blinkmAddress, 3)
if len(data) != 3 || err != nil {
data := []byte{0, 0, 0}
read, err := b.connection.Read(data)
if read != 3 || err != nil {
return []byte{}, err
}
return []byte{data[0], data[1], data[2]}, nil

View File

@ -36,6 +36,8 @@ func TestNewBlinkMDriver(t *testing.T) {
func TestNewBlinkMDriverCommands_Rgb(t *testing.T) {
blinkM := initTestBlinkMDriver()
gobottest.Assert(t, blinkM.Start(), nil)
result := blinkM.Command("Rgb")(rgb)
gobottest.Assert(t, result, nil)
}
@ -43,6 +45,8 @@ func TestNewBlinkMDriverCommands_Rgb(t *testing.T) {
func TestNewBlinkMDriverCommands_Fade(t *testing.T) {
blinkM := initTestBlinkMDriver()
gobottest.Assert(t, blinkM.Start(), nil)
result := blinkM.Command("Fade")(rgb)
gobottest.Assert(t, result, nil)
}
@ -50,11 +54,14 @@ func TestNewBlinkMDriverCommands_Fade(t *testing.T) {
func TestNewBlinkMDriverCommands_FirmwareVersion(t *testing.T) {
blinkM, adaptor := initTestBlinkDriverWithStubbedAdaptor()
gobottest.Assert(t, blinkM.Start(), nil)
param := make(map[string]interface{})
// When len(data) is 2
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{99, 1}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{99, 1})
return 2, nil
}
result := blinkM.Command("FirmwareVersion")(param)
@ -63,8 +70,9 @@ func TestNewBlinkMDriverCommands_FirmwareVersion(t *testing.T) {
gobottest.Assert(t, result.(map[string]interface{})["version"].(string), version)
// When len(data) is not 2
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{99}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{99})
return 1, nil
}
result = blinkM.Command("FirmwareVersion")(param)
@ -75,6 +83,8 @@ func TestNewBlinkMDriverCommands_FirmwareVersion(t *testing.T) {
func TestNewBlinkMDriverCommands_Color(t *testing.T) {
blinkM := initTestBlinkMDriver()
gobottest.Assert(t, blinkM.Start(), nil)
param := make(map[string]interface{})
result := blinkM.Command("Color")(param)
@ -87,6 +97,8 @@ func TestNewBlinkMDriverCommands_Color(t *testing.T) {
func TestBlinkMDriver(t *testing.T) {
blinkM := initTestBlinkMDriver()
gobottest.Assert(t, blinkM.Start(), nil)
gobottest.Refute(t, blinkM.Connection(), nil)
}
@ -95,16 +107,8 @@ func TestBlinkMDriverStart(t *testing.T) {
gobottest.Assert(t, blinkM.Start(), nil)
adaptor.i2cStartImpl = func() error {
return errors.New("start error")
}
gobottest.Assert(t, blinkM.Start(), errors.New("start error"))
adaptor.i2cStartImpl = func() error {
return nil
}
adaptor.i2cWriteImpl = func() error {
return errors.New("write error")
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, errors.New("write error")
}
gobottest.Assert(t, blinkM.Start(), errors.New("write error"))
}
@ -117,24 +121,28 @@ func TestBlinkMDriverHalt(t *testing.T) {
func TestBlinkMDriverFirmwareVersion(t *testing.T) {
blinkM, adaptor := initTestBlinkDriverWithStubbedAdaptor()
gobottest.Assert(t, blinkM.Start(), nil)
// when len(data) is 2
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{99, 1}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{99, 1})
return 2, nil
}
version, _ := blinkM.FirmwareVersion()
gobottest.Assert(t, version, "99.1")
// when len(data) is not 2
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{99}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{99})
return 1, nil
}
version, _ = blinkM.FirmwareVersion()
gobottest.Assert(t, version, "")
adaptor.i2cWriteImpl = func() error {
return errors.New("write error")
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, errors.New("write error")
}
version, err := blinkM.FirmwareVersion()
@ -144,24 +152,28 @@ func TestBlinkMDriverFirmwareVersion(t *testing.T) {
func TestBlinkMDriverColor(t *testing.T) {
blinkM, adaptor := initTestBlinkDriverWithStubbedAdaptor()
gobottest.Assert(t, blinkM.Start(), nil)
// when len(data) is 3
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{99, 1, 2}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{99, 1, 2})
return 3, nil
}
color, _ := blinkM.Color()
gobottest.Assert(t, color, []byte{99, 1, 2})
// when len(data) is not 3
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{99}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{99})
return 1, nil
}
color, _ = blinkM.Color()
gobottest.Assert(t, color, []byte{})
adaptor.i2cWriteImpl = func() error {
return errors.New("write error")
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, errors.New("write error")
}
color, err := blinkM.Color()
@ -172,8 +184,10 @@ func TestBlinkMDriverColor(t *testing.T) {
func TestBlinkMDriverFade(t *testing.T) {
blinkM, adaptor := initTestBlinkDriverWithStubbedAdaptor()
adaptor.i2cWriteImpl = func() error {
return errors.New("write error")
gobottest.Assert(t, blinkM.Start(), nil)
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, errors.New("write error")
}
err := blinkM.Fade(100, 100, 100)
@ -184,8 +198,10 @@ func TestBlinkMDriverFade(t *testing.T) {
func TestBlinkMDriverRGB(t *testing.T) {
blinkM, adaptor := initTestBlinkDriverWithStubbedAdaptor()
adaptor.i2cWriteImpl = func() error {
return errors.New("write error")
gobottest.Assert(t, blinkM.Start(), nil)
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, errors.New("write error")
}
err := blinkM.Rgb(100, 100, 100)

View File

@ -22,7 +22,8 @@ const bmp180RegisterPressureMSB = 0xF6
// Device datasheet: https://cdn-shop.adafruit.com/datasheets/BST-BMP180-DS000-09.pdf
type BMP180Driver struct {
name string
connection I2c
connector I2cConnector
connection I2cConnection
calibrationCoefficients *calibrationCoefficients
}
@ -55,10 +56,10 @@ type calibrationCoefficients struct {
}
// NewBMP180Driver creates a new driver with the i2c interface for the BMP180 device.
func NewBMP180Driver(c I2c) *BMP180Driver {
func NewBMP180Driver(c I2cConnector) *BMP180Driver {
return &BMP180Driver{
name: gobot.DefaultName("BMP180"),
connection: c,
connector: c,
calibrationCoefficients: &calibrationCoefficients{},
}
}
@ -75,11 +76,15 @@ func (d *BMP180Driver) SetName(n string) {
// Connection returns the connection of the device.
func (d *BMP180Driver) Connection() gobot.Connection {
return d.connection.(gobot.Connection)
return d.connector.(gobot.Connection)
}
// Start initializes the BMP180 and loads the calibration coefficients.
func (d *BMP180Driver) Start() (err error) {
bus := d.connector.I2cGetDefaultBus()
if d.connection, err = d.connector.I2cGetConnection(bmp180Address, bus); err != nil {
return err
}
if err := d.initialization(); err != nil {
return err
}
@ -87,9 +92,6 @@ func (d *BMP180Driver) Start() (err error) {
}
func (d *BMP180Driver) initialization() (err error) {
if err = d.connection.I2cStart(bmp180Address); err != nil {
return err
}
var coefficients []byte
// read the 11 calibration coefficients.
if coefficients, err = d.read(bmp180RegisterAC1MSB, 22); err != nil {
@ -138,7 +140,7 @@ func (d *BMP180Driver) Pressure(mode BMP180OversamplingMode) (pressure float32,
}
func (d *BMP180Driver) rawTemp() (int16, error) {
if err := d.connection.I2cWrite(bmp180Address, []byte{bmp180RegisterCtl, bmp180CmdTemp}); err != nil {
if _, err := d.connection.Write([]byte{bmp180RegisterCtl, bmp180CmdTemp}); err != nil {
return 0, err
}
time.Sleep(5 * time.Millisecond)
@ -153,14 +155,15 @@ func (d *BMP180Driver) rawTemp() (int16, error) {
}
func (d *BMP180Driver) read(address byte, n int) ([]byte, error) {
if err := d.connection.I2cWrite(bmp180Address, []byte{address}); err != nil {
if _, err := d.connection.Write([]byte{address}); err != nil {
return nil, err
}
ret, err := d.connection.I2cRead(bmp180Address, n)
if err != nil {
buf := make([]byte, n)
bytesRead, err := d.connection.Read(buf)
if bytesRead != n || err != nil {
return nil, err
}
return ret, nil
return buf, nil
}
func (d *BMP180Driver) calculateTemp(rawTemp int16) float32 {
@ -176,7 +179,7 @@ func (d *BMP180Driver) calculateB5(rawTemp int16) int32 {
}
func (d *BMP180Driver) rawPressure(mode BMP180OversamplingMode) (rawPressure int32, err error) {
if err := d.connection.I2cWrite(bmp180Address, []byte{bmp180RegisterCtl, bmp180CmdPressure + byte(mode<<6)}); err != nil {
if _, err := d.connection.Write([]byte{bmp180RegisterCtl, bmp180CmdPressure + byte(mode<<6)}); err != nil {
return 0, err
}
switch mode {

View File

@ -51,7 +51,7 @@ func TestBMP180DriverHalt(t *testing.T) {
func TestBMP180DriverMeasurements(t *testing.T) {
bmp180, adaptor := initTestBMP180DriverWithStubbedAdaptor()
adaptor.i2cReadImpl = func() ([]byte, error) {
adaptor.i2cReadImpl = func(b []byte) (int, error) {
buf := new(bytes.Buffer)
// Values from the datasheet example.
if adaptor.written[len(adaptor.written)-1] == bmp180RegisterAC1MSB {
@ -73,7 +73,8 @@ func TestBMP180DriverMeasurements(t *testing.T) {
// XLSB, not used in this test.
buf.WriteByte(0)
}
return buf.Bytes(), nil
copy(b, buf.Bytes())
return buf.Len(), nil
}
bmp180.Start()
temp, err := bmp180.Temperature()

View File

@ -9,7 +9,7 @@ type GroveLcdDriver struct {
}
// NewGroveLcdDriver creates a new driver with specified i2c interface.
func NewGroveLcdDriver(a I2c) *GroveLcdDriver {
func NewGroveLcdDriver(a I2cConnector) *GroveLcdDriver {
return &GroveLcdDriver{
JHD1313M1Driver: NewJHD1313M1Driver(a),
}
@ -20,7 +20,7 @@ type GroveAccelerometerDriver struct {
}
// NewGroveAccelerometerDriver creates a new driver with specified i2c interface
func NewGroveAccelerometerDriver(a I2c) *GroveAccelerometerDriver {
func NewGroveAccelerometerDriver(a I2cConnector) *GroveAccelerometerDriver {
return &GroveAccelerometerDriver{
MMA7660Driver: NewMMA7660Driver(a),
}

View File

@ -1,5 +1,7 @@
package i2c
import "fmt"
var rgb = map[string]interface{}{
"red": 1.0,
"green": 1.0,
@ -17,21 +19,110 @@ var blue = castColor("blue")
type i2cTestAdaptor struct {
name string
written []byte
i2cReadImpl func() ([]byte, error)
i2cWriteImpl func() error
i2cStartImpl func() error
i2cReadImpl func([]byte) (int, error)
i2cWriteImpl func([]byte) (int, error)
}
func (t *i2cTestAdaptor) I2cStart(int) (err error) {
return t.i2cStartImpl()
func (t *i2cTestAdaptor) Read(b []byte) (count int, err error) {
return t.i2cReadImpl(b)
}
func (t *i2cTestAdaptor) I2cRead(int, int) (data []byte, err error) {
return t.i2cReadImpl()
}
func (t *i2cTestAdaptor) I2cWrite(address int, b []byte) (err error) {
func (t *i2cTestAdaptor) Write(b []byte) (count int, err error) {
t.written = append(t.written, b...)
return t.i2cWriteImpl()
return t.i2cWriteImpl(b)
}
func (t *i2cTestAdaptor) Close() error {
return nil
}
func (t *i2cTestAdaptor) ReadByte() (val uint8, err error) {
bytes := []byte{0}
bytesRead, err := t.i2cReadImpl(bytes)
if err != nil {
return 0, err
}
if bytesRead != 1 {
return 0, fmt.Errorf("Buffer underrun")
}
val = bytes[0]
return
}
func (t *i2cTestAdaptor) ReadByteData(reg uint8) (val uint8, err error) {
bytes := []byte{0}
bytesRead, err := t.i2cReadImpl(bytes)
if err != nil {
return 0, err
}
if bytesRead != 1 {
return 0, fmt.Errorf("Buffer underrun")
}
val = bytes[0]
return
}
func (t *i2cTestAdaptor) ReadWordData(reg uint8) (val uint16, err error) {
bytes := []byte{0, 0}
bytesRead, err := t.i2cReadImpl(bytes)
if err != nil {
return 0, err
}
if bytesRead != 2 {
return 0, fmt.Errorf("Buffer underrun")
}
low, high := bytes[0], bytes[1]
return (uint16(high) << 8) | uint16(low), err
}
func (t *i2cTestAdaptor) ReadBlockData(_ uint8, b []byte) (n int, err error) {
bytes := make([]byte, 32)
bytesRead, err := t.i2cReadImpl(bytes)
copy(b, bytes[:bytesRead])
return bytesRead, err
}
func (t *i2cTestAdaptor) WriteByte(val uint8) (err error) {
t.written = append(t.written, val)
bytes := []byte{val}
_, err = t.i2cWriteImpl(bytes)
return
}
func (t *i2cTestAdaptor) WriteByteData(reg uint8, val uint8) (err error) {
t.written = append(t.written, reg)
t.written = append(t.written, val)
bytes := []byte{val}
_, err = t.i2cWriteImpl(bytes)
return
}
func (t *i2cTestAdaptor) WriteWordData(reg uint8, val uint16) (err error) {
t.written = append(t.written, reg)
low := uint8(val & 0xff)
high := uint8((val >> 8) & 0xff)
t.written = append(t.written, low)
t.written = append(t.written, high)
bytes := []byte{low, high}
_, err = t.i2cWriteImpl(bytes)
return
}
func (t *i2cTestAdaptor) WriteBlockData(reg uint8, b []byte) (err error) {
t.written = append(t.written, reg)
t.written = append(t.written, b...)
_, err = t.i2cWriteImpl(b)
return
}
func (t *i2cTestAdaptor) I2cGetConnection( /* address */ int /* bus */, int) (connection I2cConnection, err error) {
return t, nil
}
func (t *i2cTestAdaptor) I2cGetDefaultBus() int {
return 0
}
func (t *i2cTestAdaptor) Name() string { return t.name }
func (t *i2cTestAdaptor) SetName(n string) { t.name = n }
func (t *i2cTestAdaptor) Connect() (err error) { return }
@ -39,14 +130,11 @@ func (t *i2cTestAdaptor) Finalize() (err error) { return }
func newI2cTestAdaptor() *i2cTestAdaptor {
return &i2cTestAdaptor{
i2cReadImpl: func() ([]byte, error) {
return []byte{}, nil
i2cReadImpl: func([]byte) (int, error) {
return 0, nil
},
i2cWriteImpl: func() error {
return nil
},
i2cStartImpl: func() error {
return nil
i2cWriteImpl: func([]byte) (int, error) {
return 0, nil
},
}
}

View File

@ -7,14 +7,15 @@ const hmc6352Address = 0x21
// HMC6352Driver is a Driver for a HMC6352 digital compass
type HMC6352Driver struct {
name string
connection I2c
connector I2cConnector
connection I2cConnection
}
// NewHMC6352Driver creates a new driver with specified i2c interface
func NewHMC6352Driver(a I2c) *HMC6352Driver {
func NewHMC6352Driver(a I2cConnector) *HMC6352Driver {
return &HMC6352Driver{
name: gobot.DefaultName("HMC6352"),
connection: a,
name: gobot.DefaultName("HMC6352"),
connector: a,
}
}
@ -25,14 +26,17 @@ func (h *HMC6352Driver) Name() string { return h.name }
func (h *HMC6352Driver) SetName(n string) { h.name = n }
// Connection returns the connection for this Driver
func (h *HMC6352Driver) Connection() gobot.Connection { return h.connection.(gobot.Connection) }
func (h *HMC6352Driver) Connection() gobot.Connection { return h.connector.(gobot.Connection) }
// Start initializes the hmc6352
func (h *HMC6352Driver) Start() (err error) {
if err := h.connection.I2cStart(hmc6352Address); err != nil {
bus := h.connector.I2cGetDefaultBus()
h.connection, err = h.connector.I2cGetConnection(hmc6352Address, bus)
if err != nil {
return err
}
if err := h.connection.I2cWrite(hmc6352Address, []byte("A")); err != nil {
if _, err := h.connection.Write([]byte("A")); err != nil {
return err
}
return
@ -43,15 +47,16 @@ func (h *HMC6352Driver) Halt() (err error) { return }
// Heading returns the current heading
func (h *HMC6352Driver) Heading() (heading uint16, err error) {
if err = h.connection.I2cWrite(hmc6352Address, []byte("A")); err != nil {
if _, err = h.connection.Write([]byte("A")); err != nil {
return
}
ret, err := h.connection.I2cRead(hmc6352Address, 2)
buf := []byte{0, 0}
bytesRead, err := h.connection.Read(buf)
if err != nil {
return
}
if len(ret) == 2 {
heading = (uint16(ret[1]) + uint16(ret[0])*256) / 10
if bytesRead == 2 {
heading = (uint16(buf[1]) + uint16(buf[0])*256) / 10
return
} else {
err = ErrNotEnoughBytes

View File

@ -41,18 +41,11 @@ func TestHMC6352DriverStart(t *testing.T) {
gobottest.Assert(t, hmc.Start(), nil)
adaptor.i2cWriteImpl = func() error {
return errors.New("write error")
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, errors.New("write error")
}
err := hmc.Start()
gobottest.Assert(t, err, errors.New("write error"))
adaptor.i2cStartImpl = func() error {
return errors.New("start error")
}
err = hmc.Start()
gobottest.Assert(t, err, errors.New("start error"))
}
func TestHMC6352DriverHalt(t *testing.T) {
@ -65,8 +58,11 @@ func TestHMC6352DriverHeading(t *testing.T) {
// when len(data) is 2
hmc, adaptor := initTestHMC6352DriverWithStubbedAdaptor()
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{99, 1}, nil
gobottest.Assert(t, hmc.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{99, 1})
return 2, nil
}
heading, _ := hmc.Heading()
@ -75,8 +71,11 @@ func TestHMC6352DriverHeading(t *testing.T) {
// when len(data) is not 2
hmc, adaptor = initTestHMC6352DriverWithStubbedAdaptor()
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{99}, nil
gobottest.Assert(t, hmc.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{99})
return 1, nil
}
heading, err := hmc.Heading()
@ -86,8 +85,10 @@ func TestHMC6352DriverHeading(t *testing.T) {
// when read error
hmc, adaptor = initTestHMC6352DriverWithStubbedAdaptor()
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{}, errors.New("read error")
gobottest.Assert(t, hmc.Start(), nil)
adaptor.i2cReadImpl = func([]byte) (int, error) {
return 0, errors.New("read error")
}
heading, err = hmc.Heading()
@ -97,8 +98,10 @@ func TestHMC6352DriverHeading(t *testing.T) {
// when write error
hmc, adaptor = initTestHMC6352DriverWithStubbedAdaptor()
adaptor.i2cWriteImpl = func() error {
return errors.New("write error")
gobottest.Assert(t, hmc.Start(), nil)
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, errors.New("write error")
}
heading, err = hmc.Heading()

View File

@ -3,7 +3,7 @@ package i2c
import (
"errors"
"gobot.io/x/gobot"
"gobot.io/x/gobot/sysfs"
)
var (
@ -20,21 +20,104 @@ const (
Z = "z"
)
type I2cStarter interface {
I2cStart(address int) (err error)
// I2cConnection is a connection to an I2C device with a specified address
// on a specific bus. Used as an alternative to the I2c interface.
// Implements sysfs.I2cOperations to talk to the device, wrapping the
// calls in SetAddress to always target the specified device.
// Provided by an Adaptor by implementing the I2cConnector interface.
type I2cConnection sysfs.I2cOperations
type i2cConnection struct {
bus sysfs.I2cDevice
address int
}
type I2cReader interface {
I2cRead(address int, len int) (data []byte, err error)
func NewI2cConnection(bus sysfs.I2cDevice, address int) (connection *i2cConnection) {
return &i2cConnection{bus: bus, address: address}
}
type I2cWriter interface {
I2cWrite(address int, buf []byte) (err error)
func (c *i2cConnection) Read(data []byte) (read int, err error) {
if err := c.bus.SetAddress(c.address); err != nil {
return 0, err
}
read, err = c.bus.Read(data)
return
}
type I2c interface {
gobot.Adaptor
I2cStarter
I2cReader
I2cWriter
func (c *i2cConnection) Write(data []byte) (written int, err error) {
if err := c.bus.SetAddress(c.address); err != nil {
return 0, err
}
written, err = c.bus.Write(data)
return
}
func (c *i2cConnection) Close() error {
return c.bus.Close()
}
func (c *i2cConnection) ReadByte() (val uint8, err error) {
if err := c.bus.SetAddress(c.address); err != nil {
return 0, err
}
return c.bus.ReadByte()
}
func (c *i2cConnection) ReadByteData(reg uint8) (val uint8, err error) {
if err := c.bus.SetAddress(c.address); err != nil {
return 0, err
}
return c.bus.ReadByteData(reg)
}
func (c *i2cConnection) ReadWordData(reg uint8) (val uint16, err error) {
if err := c.bus.SetAddress(c.address); err != nil {
return 0, err
}
return c.bus.ReadWordData(reg)
}
func (c *i2cConnection) ReadBlockData(reg uint8, b []byte) (n int, err error) {
if err := c.bus.SetAddress(c.address); err != nil {
return 0, err
}
return c.bus.ReadBlockData(reg, b)
}
func (c *i2cConnection) WriteByte(val uint8) (err error) {
if err := c.bus.SetAddress(c.address); err != nil {
return err
}
return c.bus.WriteByte(val)
}
func (c *i2cConnection) WriteByteData(reg uint8, val uint8) (err error) {
if err := c.bus.SetAddress(c.address); err != nil {
return err
}
return c.bus.WriteByteData(reg, val)
}
func (c *i2cConnection) WriteWordData(reg uint8, val uint16) (err error) {
if err := c.bus.SetAddress(c.address); err != nil {
return err
}
return c.bus.WriteWordData(reg, val)
}
func (c *i2cConnection) WriteBlockData(reg uint8, b []byte) (err error) {
if err := c.bus.SetAddress(c.address); err != nil {
return err
}
return c.bus.WriteBlockData(reg, b)
}
// I2cConnector provides access to the I2C buses on platforms that support them.
type I2cConnector interface {
// I2cGetConnection returns a connection to device at the specified address
// and bus. Bus numbering starts at index 0, the range of valid buses is
// platform specific.
I2cGetConnection(address int, bus int) (device I2cConnection, err error)
// I2cGetDefaultBus returns the default I2C bus index
I2cGetDefaultBus() int
}

View File

@ -51,21 +51,21 @@ var _ gobot.Driver = (*JHD1313M1Driver)(nil)
// the position of the custom character to use.
// See SetCustomChar
var CustomLCDChars = map[string][8]byte{
"é": [8]byte{130, 132, 142, 145, 159, 144, 142, 128},
"è": [8]byte{136, 132, 142, 145, 159, 144, 142, 128},
"ê": [8]byte{132, 138, 142, 145, 159, 144, 142, 128},
"à": [8]byte{136, 134, 128, 142, 145, 147, 141, 128},
"â": [8]byte{132, 138, 128, 142, 145, 147, 141, 128},
"á": [8]byte{2, 4, 14, 1, 15, 17, 15, 0},
"î": [8]byte{132, 138, 128, 140, 132, 132, 142, 128},
"í": [8]byte{2, 4, 12, 4, 4, 4, 14, 0},
"û": [8]byte{132, 138, 128, 145, 145, 147, 141, 128},
"ù": [8]byte{136, 134, 128, 145, 145, 147, 141, 128},
"ñ": [8]byte{14, 0, 22, 25, 17, 17, 17, 0},
"ó": [8]byte{2, 4, 14, 17, 17, 17, 14, 0},
"heart": [8]byte{0, 10, 31, 31, 31, 14, 4, 0},
"smiley": [8]byte{0, 0, 10, 0, 0, 17, 14, 0},
"frowney": [8]byte{0, 0, 10, 0, 0, 0, 14, 17},
"é": {130, 132, 142, 145, 159, 144, 142, 128},
"è": {136, 132, 142, 145, 159, 144, 142, 128},
"ê": {132, 138, 142, 145, 159, 144, 142, 128},
"à": {136, 134, 128, 142, 145, 147, 141, 128},
"â": {132, 138, 128, 142, 145, 147, 141, 128},
"á": {2, 4, 14, 1, 15, 17, 15, 0},
"î": {132, 138, 128, 140, 132, 132, 142, 128},
"í": {2, 4, 12, 4, 4, 4, 14, 0},
"û": {132, 138, 128, 145, 145, 147, 141, 128},
"ù": {136, 134, 128, 145, 145, 147, 141, 128},
"ñ": {14, 0, 22, 25, 17, 17, 17, 0},
"ó": {2, 4, 14, 17, 17, 17, 14, 0},
"heart": {0, 10, 31, 31, 31, 14, 4, 0},
"smiley": {0, 0, 10, 0, 0, 17, 14, 0},
"frowney": {0, 0, 10, 0, 0, 0, 14, 17},
}
// JHD1313M1Driver is a driver for the Jhd1313m1 LCD display which has two i2c addreses,
@ -73,17 +73,19 @@ var CustomLCDChars = map[string][8]byte{
// This module was tested with the Seed Grove LCD RGB Backlight v2.0 display which requires 5V to operate.
// http://www.seeedstudio.com/wiki/Grove_-_LCD_RGB_Backlight
type JHD1313M1Driver struct {
name string
connection I2c
lcdAddress int
rgbAddress int
name string
connector I2cConnector
lcdAddress int
lcdConnection I2cConnection
rgbAddress int
rgbConnection I2cConnection
}
// NewJHD1313M1Driver creates a new driver with specified i2c interface.
func NewJHD1313M1Driver(a I2c) *JHD1313M1Driver {
func NewJHD1313M1Driver(a I2cConnector) *JHD1313M1Driver {
return &JHD1313M1Driver{
name: gobot.DefaultName("JHD1313M1"),
connection: a,
connector: a,
lcdAddress: 0x3E,
rgbAddress: 0x62,
}
@ -97,29 +99,30 @@ func (h *JHD1313M1Driver) SetName(n string) { h.name = n }
// Connection returns the driver connection to the device.
func (h *JHD1313M1Driver) Connection() gobot.Connection {
return h.connection.(gobot.Connection)
return h.connector.(gobot.Connection)
}
// Start starts the backlit and the screen and initializes the states.
func (h *JHD1313M1Driver) Start() error {
if err := h.connection.I2cStart(h.lcdAddress); err != nil {
func (h *JHD1313M1Driver) Start() (err error) {
bus := h.connector.I2cGetDefaultBus()
if h.lcdConnection, err = h.connector.I2cGetConnection(h.lcdAddress, bus); err != nil {
return err
}
if err := h.connection.I2cStart(h.rgbAddress); err != nil {
if h.rgbConnection, err = h.connector.I2cGetConnection(h.rgbAddress, bus); err != nil {
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 {
if _, err := h.lcdConnection.Write(payload); err != nil {
if _, err := h.lcdConnection.Write(payload); err != nil {
return err
}
}
time.Sleep(100 * time.Microsecond)
if err := h.connection.I2cWrite(h.lcdAddress, []byte{LCD_CMD, LCD_DISPLAYCONTROL | LCD_DISPLAYON}); err != nil {
if _, err := h.lcdConnection.Write([]byte{LCD_CMD, LCD_DISPLAYCONTROL | LCD_DISPLAYON}); err != nil {
return err
}
@ -128,7 +131,7 @@ func (h *JHD1313M1Driver) Start() error {
return err
}
if err := h.connection.I2cWrite(h.lcdAddress, []byte{LCD_CMD, LCD_ENTRYMODESET | LCD_ENTRYLEFT | LCD_ENTRYSHIFTDECREMENT}); err != nil {
if _, err := h.lcdConnection.Write([]byte{LCD_CMD, LCD_ENTRYMODESET | LCD_ENTRYLEFT | LCD_ENTRYSHIFTDECREMENT}); err != nil {
return err
}
@ -185,7 +188,7 @@ func (h *JHD1313M1Driver) Write(message string) error {
}
continue
}
if err := h.connection.I2cWrite(h.lcdAddress, []byte{LCD_DATA, byte(val)}); err != nil {
if _, err := h.lcdConnection.Write([]byte{LCD_DATA, byte(val)}); err != nil {
return err
}
}
@ -211,21 +214,25 @@ func (h *JHD1313M1Driver) SetPosition(pos int) (err error) {
func (h *JHD1313M1Driver) Scroll(leftToRight bool) error {
if leftToRight {
return h.connection.I2cWrite(h.lcdAddress, []byte{LCD_CMD, LCD_CURSORSHIFT | LCD_DISPLAYMOVE | LCD_MOVELEFT})
_, err := h.lcdConnection.Write([]byte{LCD_CMD, LCD_CURSORSHIFT | LCD_DISPLAYMOVE | LCD_MOVELEFT})
return err
}
return h.connection.I2cWrite(h.lcdAddress, []byte{LCD_CMD, LCD_CURSORSHIFT | LCD_DISPLAYMOVE | LCD_MOVERIGHT})
_, err := h.lcdConnection.Write([]byte{LCD_CMD, LCD_CURSORSHIFT | LCD_DISPLAYMOVE | LCD_MOVERIGHT})
return err
}
// Halt is a noop function.
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)})
_, err := h.rgbConnection.Write([]byte{byte(command), byte(data)})
return err
}
func (h *JHD1313M1Driver) command(buf []byte) error {
return h.connection.I2cWrite(h.lcdAddress, append([]byte{LCD_CMD}, buf...))
_, err := h.lcdConnection.Write(append([]byte{LCD_CMD}, buf...))
return err
}
// SetCustomChar sets one of the 8 CGRAM locations with a custom character.
@ -244,6 +251,6 @@ func (h *JHD1313M1Driver) SetCustomChar(pos int, charMap [8]byte) error {
if err := h.command([]byte{LCD_SETCGRAMADDR | (location << 3)}); err != nil {
return err
}
return h.connection.I2cWrite(h.lcdAddress, append([]byte{LCD_DATA}, charMap[:]...))
_, err := h.lcdConnection.Write(append([]byte{LCD_DATA}, charMap[:]...))
return err
}

View File

@ -25,7 +25,8 @@ const l3gd20hRegisterOutXLSB = 0x28 | 0x80 // set auto-increment bit.
// Device datasheet: http://www.st.com/internet/com/TECHNICAL_RESOURCES/TECHNICAL_LITERATURE/DATASHEET/DM00036465.pdf
type L3GD20HDriver struct {
name string
connection I2c
connector I2cConnector
connection I2cConnection
scale L3GD20HScale
}
@ -42,11 +43,11 @@ const (
)
// NewL3GD20HDriver creates a new driver with the i2c interface for the L3GD20H device.
func NewL3GD20HDriver(c I2c) *L3GD20HDriver {
func NewL3GD20HDriver(c I2cConnector) *L3GD20HDriver {
return &L3GD20HDriver{
name: gobot.DefaultName("L3GD20H"),
connection: c,
scale: L3GD20HScale250dps,
name: gobot.DefaultName("L3GD20H"),
connector: c,
scale: L3GD20HScale250dps,
}
}
@ -62,7 +63,7 @@ func (d *L3GD20HDriver) SetName(name string) {
// Connection returns the connection of the device.
func (d *L3GD20HDriver) Connection() gobot.Connection {
return d.connection.(gobot.Connection)
return d.connector.(gobot.Connection)
}
// Scale returns the scale sensitivity of the device.
@ -84,19 +85,21 @@ func (d *L3GD20HDriver) Start() (err error) {
}
func (d *L3GD20HDriver) initialization() (err error) {
if err = d.connection.I2cStart(l3gd20hAddress); err != nil {
bus := d.connector.I2cGetDefaultBus()
d.connection, err = d.connector.I2cGetConnection(l3gd20hAddress, bus)
if err != nil {
return err
}
// reset the gyroscope.
if err := d.connection.I2cWrite(l3gd20hAddress, []byte{l3gd20hRegisterCtl1, 0x00}); err != nil {
if _, err := d.connection.Write([]byte{l3gd20hRegisterCtl1, 0x00}); err != nil {
return err
}
// Enable Z, Y and X axis.
if err := d.connection.I2cWrite(l3gd20hAddress, []byte{l3gd20hRegisterCtl1, l3gd20hNormalMode | l3gd20hEnableZ | l3gd20hEnableY | l3gd20hEnableX}); err != nil {
if _, err := d.connection.Write([]byte{l3gd20hRegisterCtl1, l3gd20hNormalMode | l3gd20hEnableZ | l3gd20hEnableY | l3gd20hEnableX}); err != nil {
return err
}
// Set the sensitivity scale.
if err := d.connection.I2cWrite(l3gd20hAddress, []byte{l3gd20hRegisterCtl4, byte(d.scale)}); err != nil {
if _, err := d.connection.Write([]byte{l3gd20hRegisterCtl4, byte(d.scale)}); err != nil {
return err
}
return nil
@ -109,11 +112,11 @@ func (d *L3GD20HDriver) Halt() (err error) {
// XYZ returns the current change in degrees per second, for the 3 axis.
func (d *L3GD20HDriver) XYZ() (x float32, y float32, z float32, err error) {
if err := d.connection.I2cWrite(l3gd20hAddress, []byte{l3gd20hRegisterOutXLSB}); err != nil {
if _, err := d.connection.Write([]byte{l3gd20hRegisterOutXLSB}); err != nil {
return 0, 0, 0, nil
}
var measurements []byte
if measurements, err = d.connection.I2cRead(l3gd20hAddress, 6); err != nil {
measurements := make([]byte, 6)
if _, err = d.connection.Read(measurements); err != nil {
return 0, 0, 0, nil
}

View File

@ -64,12 +64,13 @@ func TestL3GD20HDriverMeasurement(t *testing.T) {
rawX := 5
rawY := 8
rawZ := -3
adaptor.i2cReadImpl = func() ([]byte, error) {
adaptor.i2cReadImpl = func(b []byte) (int, error) {
buf := new(bytes.Buffer)
binary.Write(buf, binary.LittleEndian, int16(rawX))
binary.Write(buf, binary.LittleEndian, int16(rawY))
binary.Write(buf, binary.LittleEndian, int16(rawZ))
return buf.Bytes(), nil
copy(b, buf.Bytes())
return buf.Len(), nil
}
d.Start()

View File

@ -10,24 +10,27 @@ const lidarliteAddress = 0x62
type LIDARLiteDriver struct {
name string
connection I2c
connector I2cConnector
connection I2cConnection
}
// NewLIDARLiteDriver creates a new driver with specified i2c interface
func NewLIDARLiteDriver(a I2c) *LIDARLiteDriver {
func NewLIDARLiteDriver(a I2cConnector) *LIDARLiteDriver {
return &LIDARLiteDriver{
name: gobot.DefaultName("LIDARLite"),
connection: a,
name: gobot.DefaultName("LIDARLite"),
connector: a,
}
}
func (h *LIDARLiteDriver) Name() string { return h.name }
func (h *LIDARLiteDriver) SetName(n string) { h.name = n }
func (h *LIDARLiteDriver) Connection() gobot.Connection { return h.connection.(gobot.Connection) }
func (h *LIDARLiteDriver) Connection() gobot.Connection { return h.connector.(gobot.Connection) }
// Start initialized the LIDAR
func (h *LIDARLiteDriver) Start() (err error) {
if err := h.connection.I2cStart(lidarliteAddress); err != nil {
bus := h.connector.I2cGetDefaultBus()
h.connection, err = h.connector.I2cGetConnection(lidarliteAddress, bus)
if err != nil {
return err
}
return
@ -38,35 +41,37 @@ func (h *LIDARLiteDriver) Halt() (err error) { return }
// Distance returns the current distance in cm
func (h *LIDARLiteDriver) Distance() (distance int, err error) {
if err = h.connection.I2cWrite(lidarliteAddress, []byte{0x00, 0x04}); err != nil {
if _, err = h.connection.Write([]byte{0x00, 0x04}); err != nil {
return
}
time.Sleep(20 * time.Millisecond)
if err = h.connection.I2cWrite(lidarliteAddress, []byte{0x0F}); err != nil {
if _, err = h.connection.Write([]byte{0x0F}); err != nil {
return
}
upper, err := h.connection.I2cRead(lidarliteAddress, 1)
upper := []byte{0}
bytesRead, err := h.connection.Read(upper)
if err != nil {
return
}
if len(upper) != 1 {
if bytesRead != 1 {
err = ErrNotEnoughBytes
return
}
if err = h.connection.I2cWrite(lidarliteAddress, []byte{0x10}); err != nil {
if _, err = h.connection.Write([]byte{0x10}); err != nil {
return
}
lower, err := h.connection.I2cRead(lidarliteAddress, 1)
lower := []byte{0}
bytesRead, err = h.connection.Read(lower)
if err != nil {
return
}
if len(lower) != 1 {
if bytesRead != 1 {
err = ErrNotEnoughBytes
return
}

View File

@ -37,16 +37,9 @@ func TestNewLIDARLiteDriver(t *testing.T) {
// Methods
func TestLIDARLiteDriverStart(t *testing.T) {
hmc, adaptor := initTestLIDARLiteDriverWithStubbedAdaptor()
hmc, _ := initTestLIDARLiteDriverWithStubbedAdaptor()
gobottest.Assert(t, hmc.Start(), nil)
adaptor.i2cStartImpl = func() error {
return errors.New("start error")
}
err := hmc.Start()
gobottest.Assert(t, err, errors.New("start error"))
}
func TestLIDARLiteDriverHalt(t *testing.T) {
@ -59,13 +52,17 @@ func TestLIDARLiteDriverDistance(t *testing.T) {
// when everything is happy
hmc, adaptor := initTestLIDARLiteDriverWithStubbedAdaptor()
gobottest.Assert(t, hmc.Start(), nil)
first := true
adaptor.i2cReadImpl = func() ([]byte, error) {
adaptor.i2cReadImpl = func(b []byte) (int, error) {
if first {
first = false
return []byte{99}, nil
copy(b, []byte{99})
return 1, nil
}
return []byte{1}, nil
copy(b, []byte{1})
return 1, nil
}
distance, err := hmc.Distance()
@ -76,8 +73,10 @@ func TestLIDARLiteDriverDistance(t *testing.T) {
// when insufficient bytes have been read
hmc, adaptor = initTestLIDARLiteDriverWithStubbedAdaptor()
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{}, nil
gobottest.Assert(t, hmc.Start(), nil)
adaptor.i2cReadImpl = func([]byte) (int, error) {
return 0, nil
}
distance, err = hmc.Distance()
@ -87,8 +86,10 @@ func TestLIDARLiteDriverDistance(t *testing.T) {
// when read error
hmc, adaptor = initTestLIDARLiteDriverWithStubbedAdaptor()
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{}, errors.New("read error")
gobottest.Assert(t, hmc.Start(), nil)
adaptor.i2cReadImpl = func([]byte) (int, error) {
return 0, errors.New("read error")
}
distance, err = hmc.Distance()
@ -98,8 +99,10 @@ func TestLIDARLiteDriverDistance(t *testing.T) {
// when write error
hmc, adaptor = initTestLIDARLiteDriverWithStubbedAdaptor()
adaptor.i2cWriteImpl = func() error {
return errors.New("write error")
gobottest.Assert(t, hmc.Start(), nil)
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, errors.New("write error")
}
distance, err = hmc.Distance()

View File

@ -81,7 +81,8 @@ func (mc *MCP23017Config) GetUint8Value() uint8 {
// MCP23017Driver contains the driver configuration parameters.
type MCP23017Driver struct {
name string
connection I2c
connector I2cConnector
connection I2cConnection
conf MCP23017Config
mcp23017Address int
interval time.Duration
@ -90,10 +91,10 @@ type MCP23017Driver struct {
}
// NewMCP23017Driver creates a new driver with specified i2c interface.
func NewMCP23017Driver(a I2c, conf MCP23017Config, deviceAddress int, v ...time.Duration) *MCP23017Driver {
func NewMCP23017Driver(a I2cConnector, conf MCP23017Config, deviceAddress int, v ...time.Duration) *MCP23017Driver {
m := &MCP23017Driver{
name: gobot.DefaultName("MCP23017"),
connection: a,
connector: a,
conf: conf,
mcp23017Address: deviceAddress,
Commander: gobot.NewCommander(),
@ -125,20 +126,22 @@ func (m *MCP23017Driver) Name() string { return m.name }
func (m *MCP23017Driver) SetName(n string) { m.name = n }
// Connection returns the I2c connection.
func (m *MCP23017Driver) Connection() gobot.Connection { return m.connection.(gobot.Connection) }
func (m *MCP23017Driver) Connection() gobot.Connection { return m.connector.(gobot.Connection) }
// Halt stops the driver.
func (m *MCP23017Driver) Halt() (err error) { return }
// Start writes the device configuration.
func (m *MCP23017Driver) Start() (errs error) {
if err := m.connection.I2cStart(m.mcp23017Address); err != nil {
func (m *MCP23017Driver) Start() (err error) {
bus := m.connector.I2cGetDefaultBus()
m.connection, err = m.connector.I2cGetConnection(m.mcp23017Address, bus)
if err != nil {
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 {
if _, err := m.connection.Write([]uint8{ioconReg, ioconVal}); err != nil {
return err
}
return
@ -213,7 +216,7 @@ func (m *MCP23017Driver) write(reg uint8, pin uint8, val uint8) (err error) {
if debug {
log.Printf("Writing: MCP address: 0x%X, register: 0x%X\t, value: 0x%X\n", m.mcp23017Address, reg, ioval)
}
if err = m.connection.I2cWrite(m.mcp23017Address, []uint8{reg, ioval}); err != nil {
if _, err = m.connection.Write([]uint8{reg, ioval}); err != nil {
return err
}
return nil
@ -226,17 +229,18 @@ func (m *MCP23017Driver) write(reg uint8, pin uint8, val uint8) (err error) {
func (m *MCP23017Driver) read(reg uint8) (val uint8, err error) {
register := int(reg)
bytesToRead := register + 1
v, err := m.connection.I2cRead(m.mcp23017Address, bytesToRead)
buf := make([]byte, bytesToRead)
bytesRead, err := m.connection.Read(buf)
if err != nil {
return val, err
}
if len(v) != bytesToRead {
if bytesRead != bytesToRead {
return val, fmt.Errorf("Read was unable to get %d bytes for register: 0x%X\n", bytesToRead, reg)
}
if debug {
log.Printf("Reading: MCP address: 0x%X, register:0x%X\t,value: 0x%X\n", m.mcp23017Address, reg, v[register])
log.Printf("Reading: MCP address: 0x%X, register:0x%X\t,value: 0x%X\n", m.mcp23017Address, reg, buf[register])
}
return v[register], nil
return buf[register], nil
}
// getPort return the port (A or B) given a string and the bank.

View File

@ -10,41 +10,6 @@ import (
"gobot.io/x/gobot/gobottest"
)
type i2cMcpTestAdaptor struct {
name string
i2cMcpReadImpl func(int, int) ([]byte, error)
i2cMcpWriteImpl func() error
i2cMcpStartImpl func() error
}
func (t *i2cMcpTestAdaptor) I2cStart(int) (err error) {
return t.i2cMcpStartImpl()
}
func (t *i2cMcpTestAdaptor) I2cRead(address int, numBytes int) (data []byte, err error) {
return t.i2cMcpReadImpl(address, numBytes)
}
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() (err error) { return }
func (t *i2cMcpTestAdaptor) Finalize() (err error) { return }
func newMcpI2cTestAdaptor() *i2cMcpTestAdaptor {
return &i2cMcpTestAdaptor{
i2cMcpReadImpl: func(address int, numBytes int) ([]byte, error) {
return []byte{}, nil
},
i2cMcpWriteImpl: func() error {
return nil
},
i2cMcpStartImpl: func() error {
return nil
},
}
}
var pinValPort = map[string]interface{}{
"pin": uint8(7),
"val": uint8(0),
@ -61,19 +26,19 @@ func initTestMCP23017Driver(b uint8) (driver *MCP23017Driver) {
return
}
func initTestMCP23017DriverWithStubbedAdaptor(b uint8) (*MCP23017Driver, *i2cMcpTestAdaptor) {
adaptor := newMcpI2cTestAdaptor()
func initTestMCP23017DriverWithStubbedAdaptor(b uint8) (*MCP23017Driver, *i2cTestAdaptor) {
adaptor := newI2cTestAdaptor()
return NewMCP23017Driver(adaptor, MCP23017Config{Bank: b}, 0x20), adaptor
}
func TestNewMCP23017Driver(t *testing.T) {
var bm interface{} = NewMCP23017Driver(newMcpI2cTestAdaptor(), MCP23017Config{}, 0x20)
var bm interface{} = NewMCP23017Driver(newI2cTestAdaptor(), MCP23017Config{}, 0x20)
_, ok := bm.(*MCP23017Driver)
if !ok {
t.Errorf("NewMCP23017Driver() should have returned a *MCP23017Driver")
}
b := NewMCP23017Driver(newMcpI2cTestAdaptor(), MCP23017Config{}, 0x20)
b := NewMCP23017Driver(newI2cTestAdaptor(), MCP23017Config{}, 0x20)
gobottest.Refute(t, b.Connection(), nil)
}
@ -82,17 +47,11 @@ func TestMCP23017DriverStart(t *testing.T) {
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cMcpWriteImpl = func() error {
return errors.New("write error")
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, errors.New("write error")
}
err := mcp.Start()
gobottest.Assert(t, err, errors.New("write error"))
adaptor.i2cMcpStartImpl = func() error {
return errors.New("start error")
}
err = mcp.Start()
gobottest.Assert(t, err, errors.New("start error"))
}
func TestMCP23017DriverHalt(t *testing.T) {
@ -102,11 +61,13 @@ func TestMCP23017DriverHalt(t *testing.T) {
func TestMCP23017DriverCommandsWriteGPIO(t *testing.T) {
mcp, adaptor := initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
adaptor.i2cMcpWriteImpl = func() error {
return nil
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, nil
}
result := mcp.Command("WriteGPIO")(pinValPort)
gobottest.Assert(t, result.(map[string]interface{})["err"], nil)
@ -114,8 +75,10 @@ func TestMCP23017DriverCommandsWriteGPIO(t *testing.T) {
func TestMCP23017DriverCommandsReadGPIO(t *testing.T) {
mcp, adaptor := initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
result := mcp.Command("ReadGPIO")(pinPort)
gobottest.Assert(t, result.(map[string]interface{})["err"], nil)
@ -123,22 +86,27 @@ func TestMCP23017DriverCommandsReadGPIO(t *testing.T) {
func TestMCP23017DriverWriteGPIO(t *testing.T) {
mcp, adaptor := initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
adaptor.i2cMcpWriteImpl = func() error {
return nil
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, nil
}
err := mcp.WriteGPIO(7, 0, "A")
gobottest.Assert(t, err, nil)
}
func TestMCP23017DriverCommandsWriteGPIOErrIODIR(t *testing.T) {
mcp, adaptor := initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
adaptor.i2cMcpWriteImpl = func() error {
return errors.New("write error")
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, errors.New("write error")
}
err := mcp.WriteGPIO(7, 0, "A")
gobottest.Assert(t, err, errors.New("write error"))
@ -146,16 +114,18 @@ func TestMCP23017DriverCommandsWriteGPIOErrIODIR(t *testing.T) {
func TestMCP23017DriverCommandsWriteGPIOErrOLAT(t *testing.T) {
mcp, adaptor := initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
numCalls := 1
adaptor.i2cMcpWriteImpl = func() error {
adaptor.i2cWriteImpl = func([]byte) (int, error) {
if numCalls == 2 {
return errors.New("write error")
return 0, errors.New("write error")
}
numCalls++
return nil
return 0, nil
}
err := mcp.WriteGPIO(7, 0, "A")
gobottest.Assert(t, err, errors.New("write error"))
@ -163,24 +133,30 @@ func TestMCP23017DriverCommandsWriteGPIOErrOLAT(t *testing.T) {
func TestMCP23017DriverReadGPIO(t *testing.T) {
mcp, adaptor := initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
val, _ := mcp.ReadGPIO(7, "A")
gobottest.Assert(t, val, uint8(0))
// read error
mcp, adaptor = initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), errors.New("read error")
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), errors.New("read error")
}
_, err := mcp.ReadGPIO(7, "A")
gobottest.Assert(t, err, errors.New("read error"))
// empty value from read
mcp, adaptor = initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), errors.New("Read came back with no data")
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), errors.New("Read came back with no data")
}
_, err = mcp.ReadGPIO(7, "A")
gobottest.Assert(t, err, errors.New("Read came back with no data"))
@ -188,22 +164,26 @@ func TestMCP23017DriverReadGPIO(t *testing.T) {
func TestMCP23017DriverPinMode(t *testing.T) {
mcp, adaptor := initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
adaptor.i2cMcpWriteImpl = func() error {
return nil
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, nil
}
err := mcp.PinMode(7, 0, "A")
gobottest.Assert(t, err, nil)
// write error
mcp, adaptor = initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
adaptor.i2cMcpWriteImpl = func() error {
return errors.New("write error")
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, errors.New("write error")
}
err = mcp.PinMode(7, 0, "A")
gobottest.Assert(t, err, errors.New("write error"))
@ -211,22 +191,26 @@ func TestMCP23017DriverPinMode(t *testing.T) {
func TestMCP23017DriverSetPullUp(t *testing.T) {
mcp, adaptor := initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
adaptor.i2cMcpWriteImpl = func() error {
return nil
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, nil
}
err := mcp.SetPullUp(7, 0, "A")
gobottest.Assert(t, err, nil)
// write error
mcp, adaptor = initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
adaptor.i2cMcpWriteImpl = func() error {
return errors.New("write error")
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, errors.New("write error")
}
err = mcp.SetPullUp(7, 0, "A")
gobottest.Assert(t, err, errors.New("write error"))
@ -234,22 +218,26 @@ func TestMCP23017DriverSetPullUp(t *testing.T) {
func TestMCP23017DriverSetGPIOPolarity(t *testing.T) {
mcp, adaptor := initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
adaptor.i2cMcpWriteImpl = func() error {
return nil
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, nil
}
err := mcp.SetGPIOPolarity(7, 0, "A")
gobottest.Assert(t, err, nil)
// write error
mcp, adaptor = initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
adaptor.i2cMcpWriteImpl = func() error {
return errors.New("write error")
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, errors.New("write error")
}
err = mcp.SetGPIOPolarity(7, 0, "A")
gobottest.Assert(t, err, errors.New("write error"))
@ -259,43 +247,51 @@ func TestMCP23017DriverSetGPIOPolarity(t *testing.T) {
func TestMCP23017DriverWrite(t *testing.T) {
// clear bit
mcp, adaptor := initTestMCP23017DriverWithStubbedAdaptor(0)
gobottest.Assert(t, mcp.Start(), nil)
port := mcp.getPort("A")
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
adaptor.i2cMcpWriteImpl = func() error {
return nil
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, nil
}
err := mcp.write(port.IODIR, uint8(7), 0)
gobottest.Assert(t, err, nil)
// set bit
mcp, adaptor = initTestMCP23017DriverWithStubbedAdaptor(0)
gobottest.Assert(t, mcp.Start(), nil)
port = mcp.getPort("B")
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
adaptor.i2cMcpWriteImpl = func() error {
return nil
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, nil
}
err = mcp.write(port.IODIR, uint8(7), 1)
gobottest.Assert(t, err, nil)
// write error
mcp, adaptor = initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
adaptor.i2cMcpWriteImpl = func() error {
return errors.New("write error")
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, errors.New("write error")
}
err = mcp.write(port.IODIR, uint8(7), 0)
gobottest.Assert(t, err, errors.New("write error"))
// read error
mcp, adaptor = initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), errors.New("read error")
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), errors.New("read error")
}
err = mcp.write(port.IODIR, uint8(7), 0)
gobottest.Assert(t, err, errors.New("read error"))
@ -303,11 +299,11 @@ func TestMCP23017DriverWrite(t *testing.T) {
//debug
debug = true
log.SetOutput(ioutil.Discard)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), nil
}
adaptor.i2cMcpWriteImpl = func() error {
return nil
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 0, nil
}
err = mcp.write(port.IODIR, uint8(7), 1)
gobottest.Assert(t, err, nil)
@ -318,17 +314,22 @@ func TestMCP23017DriverWrite(t *testing.T) {
func TestMCP23017DriverReadPort(t *testing.T) {
// read
mcp, adaptor := initTestMCP23017DriverWithStubbedAdaptor(0)
gobottest.Assert(t, mcp.Start(), nil)
port := mcp.getPort("A")
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return []byte{255}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{255})
return 1, nil
}
val, _ := mcp.read(port.IODIR)
gobottest.Assert(t, val, uint8(255))
// read error
mcp, adaptor = initTestMCP23017DriverWithStubbedAdaptor(0)
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return make([]byte, b), errors.New("read error")
gobottest.Assert(t, mcp.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return len(b), errors.New("read error")
}
val, err := mcp.read(port.IODIR)
@ -337,9 +338,11 @@ func TestMCP23017DriverReadPort(t *testing.T) {
// read
mcp, adaptor = initTestMCP23017DriverWithStubbedAdaptor(0)
gobottest.Assert(t, mcp.Start(), nil)
port = mcp.getPort("A")
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return []byte{}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
return 0, nil
}
_, err = mcp.read(port.IODIR)
gobottest.Assert(t, err, errors.New("Read was unable to get 1 bytes for register: 0x0\n"))
@ -348,10 +351,13 @@ func TestMCP23017DriverReadPort(t *testing.T) {
debug = true
log.SetOutput(ioutil.Discard)
mcp, adaptor = initTestMCP23017DriverWithStubbedAdaptor(0)
gobottest.Assert(t, mcp.Start(), nil)
port = mcp.getPort("A")
adaptor.i2cMcpReadImpl = func(a int, b int) ([]byte, error) {
return []byte{255}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{255})
return 1, nil
}
val, _ = mcp.read(port.IODIR)

View File

@ -32,36 +32,40 @@ const (
type MMA7660Driver struct {
name string
connection I2c
connector I2cConnector
connection I2cConnection
}
// NewMMA7660Driver creates a new driver with specified i2c interface
func NewMMA7660Driver(a I2c) *MMA7660Driver {
func NewMMA7660Driver(a I2cConnector) *MMA7660Driver {
return &MMA7660Driver{
name: gobot.DefaultName("MMA7660"),
connection: a,
name: gobot.DefaultName("MMA7660"),
connector: a,
}
}
func (h *MMA7660Driver) Name() string { return h.name }
func (h *MMA7660Driver) SetName(n string) { h.name = n }
func (h *MMA7660Driver) Connection() gobot.Connection { return h.connection.(gobot.Connection) }
func (h *MMA7660Driver) Connection() gobot.Connection { return h.connector.(gobot.Connection) }
// Start initialized the mma7660
func (h *MMA7660Driver) Start() (err error) {
if err := h.connection.I2cStart(mma7660Address); err != nil {
bus := h.connector.I2cGetDefaultBus()
h.connection, err = h.connector.I2cGetConnection(mma7660Address, bus)
if err != nil {
return err
}
if err := h.connection.I2cWrite(mma7660Address, []byte{MMA7660_MODE, MMA7660_STAND_BY}); err != nil {
if _, err := h.connection.Write([]byte{MMA7660_MODE, MMA7660_STAND_BY}); err != nil {
return err
}
if err := h.connection.I2cWrite(mma7660Address, []byte{MMA7660_SR, MMA7660_AUTO_SLEEP_32}); err != nil {
if _, err := h.connection.Write([]byte{MMA7660_SR, MMA7660_AUTO_SLEEP_32}); err != nil {
return err
}
if err := h.connection.I2cWrite(mma7660Address, []byte{MMA7660_MODE, MMA7660_ACTIVE}); err != nil {
if _, err := h.connection.Write([]byte{MMA7660_MODE, MMA7660_ACTIVE}); err != nil {
return err
}
@ -78,26 +82,27 @@ func (h *MMA7660Driver) Acceleration(x, y, z float64) (ax, ay, az float64) {
// XYZ returns the raw x,y and z axis from the mma7660
func (h *MMA7660Driver) XYZ() (x float64, y float64, z float64, err error) {
ret, err := h.connection.I2cRead(mma7660Address, 3)
buf := []byte{0, 0, 0}
bytesRead, err := h.connection.Read(buf)
if err != nil {
return
}
if len(ret) != 3 {
if bytesRead != 3 {
err = ErrNotEnoughBytes
return
}
for _, val := range ret {
for _, val := range buf {
if ((val >> 6) & 0x01) == 1 {
err = ErrNotReady
return
}
}
x = float64((int8(ret[0]) << 2)) / 4.0
y = float64((int8(ret[1]) << 2)) / 4.0
z = float64((int8(ret[2]) << 2)) / 4.0
x = float64((int8(buf[0]) << 2)) / 4.0
y = float64((int8(buf[1]) << 2)) / 4.0
z = float64((int8(buf[2]) << 2)) / 4.0
return
}

View File

@ -26,7 +26,8 @@ const MPL115A2_REGISTER_STARTCONVERSION = 0x12
type MPL115A2Driver struct {
name string
connection I2c
connector I2cConnector
connection I2cConnection
interval time.Duration
gobot.Eventer
A0 float32
@ -38,12 +39,12 @@ type MPL115A2Driver struct {
}
// NewMPL115A2Driver creates a new driver with specified i2c interface
func NewMPL115A2Driver(a I2c, v ...time.Duration) *MPL115A2Driver {
func NewMPL115A2Driver(a I2cConnector, v ...time.Duration) *MPL115A2Driver {
m := &MPL115A2Driver{
name: gobot.DefaultName("MPL115A2"),
connection: a,
Eventer: gobot.NewEventer(),
interval: 10 * time.Millisecond,
name: gobot.DefaultName("MPL115A2"),
connector: a,
Eventer: gobot.NewEventer(),
interval: 10 * time.Millisecond,
}
if len(v) > 0 {
@ -55,7 +56,7 @@ func NewMPL115A2Driver(a I2c, v ...time.Duration) *MPL115A2Driver {
func (h *MPL115A2Driver) Name() string { return h.name }
func (h *MPL115A2Driver) SetName(n string) { h.name = n }
func (h *MPL115A2Driver) Connection() gobot.Connection { return h.connection.(gobot.Connection) }
func (h *MPL115A2Driver) Connection() gobot.Connection { return h.connector.(gobot.Connection) }
// Start writes initialization bytes and reads from adaptor
// using specified interval to accelerometer andtemperature data
@ -70,25 +71,26 @@ func (h *MPL115A2Driver) Start() (err error) {
go func() {
for {
if err := h.connection.I2cWrite(mpl115a2Address, []byte{MPL115A2_REGISTER_STARTCONVERSION, 0}); err != nil {
if _, err := h.connection.Write([]byte{MPL115A2_REGISTER_STARTCONVERSION, 0}); err != nil {
h.Publish(h.Event(Error), err)
continue
}
time.Sleep(5 * time.Millisecond)
if err := h.connection.I2cWrite(mpl115a2Address, []byte{MPL115A2_REGISTER_PRESSURE_MSB}); err != nil {
if _, err := h.connection.Write([]byte{MPL115A2_REGISTER_PRESSURE_MSB}); err != nil {
h.Publish(h.Event(Error), err)
continue
}
ret, err := h.connection.I2cRead(mpl115a2Address, 4)
data := []byte{0, 0, 0, 0}
bytesRead, err := h.connection.Read(data)
if err != nil {
h.Publish(h.Event(Error), err)
continue
}
if len(ret) == 4 {
buf := bytes.NewBuffer(ret)
if bytesRead == 4 {
buf := bytes.NewBuffer(data)
binary.Read(buf, binary.BigEndian, &pressure)
binary.Read(buf, binary.BigEndian, &temperature)
@ -114,17 +116,21 @@ func (h *MPL115A2Driver) initialization() (err error) {
var coB2 int16
var coC12 int16
if err = h.connection.I2cStart(mpl115a2Address); err != nil {
return
}
if err = h.connection.I2cWrite(mpl115a2Address, []byte{MPL115A2_REGISTER_A0_COEFF_MSB}); err != nil {
return
}
ret, err := h.connection.I2cRead(mpl115a2Address, 8)
bus := h.connector.I2cGetDefaultBus()
h.connection, err = h.connector.I2cGetConnection(mpl115a2Address, bus)
if err != nil {
return err
}
if _, err = h.connection.Write([]byte{MPL115A2_REGISTER_A0_COEFF_MSB}); err != nil {
return
}
buf := bytes.NewBuffer(ret)
data := make([]byte, 8)
if _, err = h.connection.Read(data); err != nil {
return
}
buf := bytes.NewBuffer(data)
binary.Read(buf, binary.BigEndian, &coA0)
binary.Read(buf, binary.BigEndian, &coB1)

View File

@ -46,8 +46,9 @@ func TestMPL115A2Driver(t *testing.T) {
func TestMPL115A2DriverStart(t *testing.T) {
mpl, adaptor := initTestMPL115A2DriverWithStubbedAdaptor()
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{0x00, 0x01, 0x02, 0x04}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{0x00, 0x01, 0x02, 0x04})
return 4, nil
}
gobottest.Assert(t, mpl.Start(), nil)
time.Sleep(100 * time.Millisecond)

View File

@ -34,7 +34,8 @@ type ThreeDData struct {
type MPU6050Driver struct {
name string
connection I2c
connector I2cConnector
connection I2cConnection
interval time.Duration
Accelerometer ThreeDData
Gyroscope ThreeDData
@ -43,12 +44,12 @@ type MPU6050Driver struct {
}
// NewMPU6050Driver creates a new driver with specified i2c interface
func NewMPU6050Driver(a I2c, v ...time.Duration) *MPU6050Driver {
func NewMPU6050Driver(a I2cConnector, v ...time.Duration) *MPU6050Driver {
m := &MPU6050Driver{
name: gobot.DefaultName("MPM6050"),
connection: a,
interval: 10 * time.Millisecond,
Eventer: gobot.NewEventer(),
name: gobot.DefaultName("MPM6050"),
connector: a,
interval: 10 * time.Millisecond,
Eventer: gobot.NewEventer(),
}
if len(v) > 0 {
@ -61,7 +62,7 @@ func NewMPU6050Driver(a I2c, v ...time.Duration) *MPU6050Driver {
func (h *MPU6050Driver) Name() string { return h.name }
func (h *MPU6050Driver) SetName(n string) { h.name = n }
func (h *MPU6050Driver) Connection() gobot.Connection { return h.connection.(gobot.Connection) }
func (h *MPU6050Driver) Connection() gobot.Connection { return h.connector.(gobot.Connection) }
// Start writes initialization bytes and reads from adaptor
// using specified interval to accelerometer andtemperature data
@ -72,17 +73,18 @@ func (h *MPU6050Driver) Start() (err error) {
go func() {
for {
if err := h.connection.I2cWrite(mpu6050Address, []byte{MPU6050_RA_ACCEL_XOUT_H}); err != nil {
if _, err := h.connection.Write([]byte{MPU6050_RA_ACCEL_XOUT_H}); err != nil {
h.Publish(h.Event(Error), err)
continue
}
ret, err := h.connection.I2cRead(mpu6050Address, 14)
data := make([]byte, 14)
_, err := h.connection.Read(data)
if err != nil {
h.Publish(h.Event(Error), err)
continue
}
buf := bytes.NewBuffer(ret)
buf := bytes.NewBuffer(data)
binary.Read(buf, binary.BigEndian, &h.Accelerometer)
binary.Read(buf, binary.BigEndian, &h.Temperature)
binary.Read(buf, binary.BigEndian, &h.Gyroscope)
@ -97,12 +99,14 @@ func (h *MPU6050Driver) Start() (err error) {
func (h *MPU6050Driver) Halt() (err error) { return }
func (h *MPU6050Driver) initialize() (err error) {
if err = h.connection.I2cStart(mpu6050Address); err != nil {
return
bus := h.connector.I2cGetDefaultBus()
h.connection, err = h.connector.I2cGetConnection(mpu6050Address, bus)
if err != nil {
return err
}
// setClockSource
if err = h.connection.I2cWrite(mpu6050Address, []byte{MPU6050_RA_PWR_MGMT_1,
if _, err = h.connection.Write([]byte{MPU6050_RA_PWR_MGMT_1,
MPU6050_PWR1_CLKSEL_BIT,
MPU6050_PWR1_CLKSEL_LENGTH,
MPU6050_CLOCK_PLL_XGYRO}); err != nil {
@ -110,7 +114,7 @@ func (h *MPU6050Driver) initialize() (err error) {
}
// setFullScaleGyroRange
if err = h.connection.I2cWrite(mpu6050Address, []byte{MPU6050_RA_GYRO_CONFIG,
if _, err = h.connection.Write([]byte{MPU6050_RA_GYRO_CONFIG,
MPU6050_GCONFIG_FS_SEL_BIT,
MPU6050_GCONFIG_FS_SEL_LENGTH,
MPU6050_GYRO_FS_250}); err != nil {
@ -118,7 +122,7 @@ func (h *MPU6050Driver) initialize() (err error) {
}
// setFullScaleAccelRange
if err = h.connection.I2cWrite(mpu6050Address, []byte{MPU6050_RA_ACCEL_CONFIG,
if _, err = h.connection.Write([]byte{MPU6050_RA_ACCEL_CONFIG,
MPU6050_ACONFIG_AFS_SEL_BIT,
MPU6050_ACONFIG_AFS_SEL_LENGTH,
MPU6050_ACCEL_FS_2}); err != nil {
@ -126,7 +130,7 @@ func (h *MPU6050Driver) initialize() (err error) {
}
// setSleepEnabled
if err = h.connection.I2cWrite(mpu6050Address, []byte{MPU6050_RA_PWR_MGMT_1,
if _, err = h.connection.Write([]byte{MPU6050_RA_PWR_MGMT_1,
MPU6050_PWR1_ENABLE_BIT,
0}); err != nil {
return

View File

@ -13,6 +13,7 @@
* See the License for the specific language governing permissions and
* limitations under the License.
*/
package i2c
// SHT3xDriver is a driver for the SHT3x-D based devices.
@ -55,7 +56,8 @@ type SHT3xDriver struct {
Units string
name string
connection I2c
connector I2cConnector
connection I2cConnection
sht3xAddress int
accuracy byte
delay time.Duration
@ -63,11 +65,11 @@ type SHT3xDriver struct {
}
// NewSHT3xDriver creates a new driver with specified i2c interface
func NewSHT3xDriver(a I2c) *SHT3xDriver {
func NewSHT3xDriver(a I2cConnector) *SHT3xDriver {
s := &SHT3xDriver{
Units: "C",
name: gobot.DefaultName("SHT3x"),
connection: a,
connector: a,
sht3xAddress: SHT3xAddressA,
crcTable: crc8.MakeTable(crc8Params),
}
@ -82,11 +84,12 @@ func (s *SHT3xDriver) Name() string { return s.name }
func (s *SHT3xDriver) SetName(n string) { s.name = n }
// Connection returns the connection for this Driver
func (s *SHT3xDriver) Connection() gobot.Connection { return s.connection.(gobot.Connection) }
func (s *SHT3xDriver) Connection() gobot.Connection { return s.connector.(gobot.Connection) }
// Start initializes the SHT3x
func (s *SHT3xDriver) Start() (err error) {
err = s.connection.I2cStart(s.sht3xAddress)
bus := s.connector.I2cGetDefaultBus()
s.connection, err = s.connector.I2cGetConnection(s.sht3xAddress, bus)
return
}
@ -145,7 +148,8 @@ func (s *SHT3xDriver) SetHeater(enabled bool) (err error) {
if true == enabled {
out[1] = 0x6d
}
return s.connection.I2cWrite(s.sht3xAddress, out)
_, err = s.connection.Write(out)
return
}
// Sample returns the temperature in celsius and relative humidity for one sample
@ -188,7 +192,7 @@ func (s *SHT3xDriver) getStatusRegister() (status uint16, err error) {
// sendCommandDelayGetResponse is a helper function to reduce duplicated code
func (s *SHT3xDriver) sendCommandDelayGetResponse(send []byte, delay *time.Duration, expect int) (read []uint16, err error) {
if err = s.connection.I2cWrite(s.sht3xAddress, send); err != nil {
if _, err = s.connection.Write(send); err != nil {
return
}
@ -196,23 +200,24 @@ func (s *SHT3xDriver) sendCommandDelayGetResponse(send []byte, delay *time.Durat
time.Sleep(*delay)
}
got, err := s.connection.I2cRead(s.sht3xAddress, 3*expect)
buf := make([]byte, 3*expect)
got, err := s.connection.Read(buf)
if err != nil {
return
}
if len(got) != (3 * expect) {
if got != (3 * expect) {
err = ErrNotEnoughBytes
return
}
read = make([]uint16, expect)
for i := 0; i < expect; i++ {
crc := crc8.Checksum(got[i*3:i*3+2], s.crcTable)
if got[i*3+2] != crc {
crc := crc8.Checksum(buf[i*3:i*3+2], s.crcTable)
if buf[i*3+2] != crc {
err = ErrInvalidCrc
return
}
read[i] = uint16(got[i*3])<<8 | uint16(got[i*3+1])
read[i] = uint16(buf[i*3])<<8 | uint16(buf[i*3+1])
}
return

View File

@ -40,16 +40,9 @@ func TestNewSHT3xDriver(t *testing.T) {
// Test Start
func TestSHT3xDriverStart(t *testing.T) {
sht3x, adaptor := initTestSHT3xDriverWithStubbedAdaptor()
sht3x, _ := initTestSHT3xDriverWithStubbedAdaptor()
gobottest.Assert(t, sht3x.Start(), nil)
adaptor.i2cStartImpl = func() error {
return errors.New("start error")
}
err := sht3x.Start()
gobottest.Assert(t, err, errors.New("start error"))
}
// Test Halt
@ -90,8 +83,11 @@ func TestSHT3xDriverSetAccuracy(t *testing.T) {
func TestSHT3xDriverSampleNormal(t *testing.T) {
sht3x, adaptor := initTestSHT3xDriverWithStubbedAdaptor()
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{0xbe, 0xef, 0x92, 0xbe, 0xef, 0x92}, nil
gobottest.Assert(t, sht3x.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{0xbe, 0xef, 0x92, 0xbe, 0xef, 0x92})
return 6, nil
}
temp, rh, _ := sht3x.Sample()
@ -107,17 +103,21 @@ func TestSHT3xDriverSampleNormal(t *testing.T) {
func TestSHT3xDriverSampleBadCrc(t *testing.T) {
sht3x, adaptor := initTestSHT3xDriverWithStubbedAdaptor()
gobottest.Assert(t, sht3x.Start(), nil)
// Check that the 1st crc failure is caught
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{0xbe, 0xef, 0x00, 0xbe, 0xef, 0x92}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{0xbe, 0xef, 0x00, 0xbe, 0xef, 0x92})
return 6, nil
}
_, _, err := sht3x.Sample()
gobottest.Assert(t, err, ErrInvalidCrc)
// Check that the 2nd crc failure is caught
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{0xbe, 0xef, 0x92, 0xbe, 0xef, 0x00}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{0xbe, 0xef, 0x92, 0xbe, 0xef, 0x00})
return 6, nil
}
_, _, err = sht3x.Sample()
@ -127,9 +127,12 @@ func TestSHT3xDriverSampleBadCrc(t *testing.T) {
func TestSHT3xDriverSampleBadRead(t *testing.T) {
sht3x, adaptor := initTestSHT3xDriverWithStubbedAdaptor()
gobottest.Assert(t, sht3x.Start(), nil)
// Check that the 1st crc failure is caught
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{0xbe, 0xef, 0x00, 0xbe, 0xef}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{0xbe, 0xef, 0x00, 0xbe, 0xef})
return 5, nil
}
_, _, err := sht3x.Sample()
@ -139,9 +142,12 @@ func TestSHT3xDriverSampleBadRead(t *testing.T) {
func TestSHT3xDriverSampleUnits(t *testing.T) {
sht3x, adaptor := initTestSHT3xDriverWithStubbedAdaptor()
gobottest.Assert(t, sht3x.Start(), nil)
// Check that the 1st crc failure is caught
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{0xbe, 0xef, 0x92, 0xbe, 0xef, 0x92}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{0xbe, 0xef, 0x92, 0xbe, 0xef, 0x92})
return 6, nil
}
sht3x.Units = "K"
@ -153,28 +159,31 @@ func TestSHT3xDriverSampleUnits(t *testing.T) {
func TestSHT3xDriverSCDGRIoFailures(t *testing.T) {
sht3x, adaptor := initTestSHT3xDriverWithStubbedAdaptor()
gobottest.Assert(t, sht3x.Start(), nil)
invalidRead := errors.New("Read error")
invalidWrite := errors.New("Write error")
// Only send 5 bytes
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{0xbe, 0xef, 0x92, 0xbe, 0xef}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{0xbe, 0xef, 0x92, 0xbe, 0xef})
return 5, nil
}
_, err := sht3x.sendCommandDelayGetResponse(nil, nil, 2)
gobottest.Assert(t, err, ErrNotEnoughBytes)
// Don't read any bytes and return an error
adaptor.i2cReadImpl = func() ([]byte, error) {
return nil, invalidRead
adaptor.i2cReadImpl = func([]byte) (int, error) {
return 0, invalidRead
}
_, err = sht3x.sendCommandDelayGetResponse(nil, nil, 1)
gobottest.Assert(t, err, invalidRead)
// Don't write any bytes and return an error
adaptor.i2cWriteImpl = func() error {
return invalidWrite
adaptor.i2cWriteImpl = func([]byte) (int, error) {
return 42, invalidWrite
}
_, err = sht3x.sendCommandDelayGetResponse(nil, nil, 1)
@ -185,9 +194,12 @@ func TestSHT3xDriverSCDGRIoFailures(t *testing.T) {
func TestSHT3xDriverHeater(t *testing.T) {
sht3x, adaptor := initTestSHT3xDriverWithStubbedAdaptor()
gobottest.Assert(t, sht3x.Start(), nil)
// heater enabled
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{0x20, 0x00, 0x5d}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{0x20, 0x00, 0x5d})
return 3, nil
}
status, err := sht3x.Heater()
@ -195,8 +207,9 @@ func TestSHT3xDriverHeater(t *testing.T) {
gobottest.Assert(t, status, true)
// heater disabled
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{0x00, 0x00, 0x81}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{0x00, 0x00, 0x81})
return 3, nil
}
status, err = sht3x.Heater()
@ -204,16 +217,18 @@ func TestSHT3xDriverHeater(t *testing.T) {
gobottest.Assert(t, status, false)
// heater crc failed
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{0x00, 0x00, 0x00}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{0x00, 0x00, 0x00})
return 3, nil
}
status, err = sht3x.Heater()
gobottest.Assert(t, err, ErrInvalidCrc)
// heater read failed
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{0x00, 0x00}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{0x00, 0x00})
return 2, nil
}
status, err = sht3x.Heater()
@ -224,6 +239,8 @@ func TestSHT3xDriverHeater(t *testing.T) {
func TestSHT3xDriverSetHeater(t *testing.T) {
sht3x, _ := initTestSHT3xDriverWithStubbedAdaptor()
gobottest.Assert(t, sht3x.Start(), nil)
sht3x.SetHeater(false)
sht3x.SetHeater(true)
}
@ -231,9 +248,12 @@ func TestSHT3xDriverSetHeater(t *testing.T) {
// Test SerialNumber
func TestSHT3xDriverSerialNumber(t *testing.T) {
sht3x, adaptor := initTestSHT3xDriverWithStubbedAdaptor()
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{0x20, 0x00, 0x5d, 0xbe, 0xef, 0x92}, nil
gobottest.Assert(t, sht3x.Start(), nil)
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{0x20, 0x00, 0x5d, 0xbe, 0xef, 0x92})
return 6, nil
}
sn, err := sht3x.SerialNumber()

View File

@ -10,7 +10,8 @@ const wiichuckAddress = 0x52
type WiichuckDriver struct {
name string
connection I2c
connector I2cConnector
connection I2cConnection
interval time.Duration
pauseTime time.Duration
gobot.Eventer
@ -25,13 +26,13 @@ type WiichuckDriver struct {
// "c" - Gets triggered every interval amount of time if the c button is pressed
// "joystick" - Gets triggered every "interval" amount of time if a joystick event occurred, you can access values x, y
// "error" - Gets triggered whenever the WiichuckDriver encounters an error
func NewWiichuckDriver(a I2c, v ...time.Duration) *WiichuckDriver {
func NewWiichuckDriver(a I2cConnector, v ...time.Duration) *WiichuckDriver {
w := &WiichuckDriver{
name: gobot.DefaultName("Wiichuck"),
connection: a,
interval: 10 * time.Millisecond,
pauseTime: 1 * time.Millisecond,
Eventer: gobot.NewEventer(),
name: gobot.DefaultName("Wiichuck"),
connector: a,
interval: 10 * time.Millisecond,
pauseTime: 1 * time.Millisecond,
Eventer: gobot.NewEventer(),
joystick: map[string]float64{
"sy_origin": -1,
"sx_origin": -1,
@ -56,33 +57,36 @@ func NewWiichuckDriver(a I2c, v ...time.Duration) *WiichuckDriver {
}
func (w *WiichuckDriver) Name() string { return w.name }
func (w *WiichuckDriver) SetName(n string) { w.name = n }
func (w *WiichuckDriver) Connection() gobot.Connection { return w.connection.(gobot.Connection) }
func (w *WiichuckDriver) Connection() gobot.Connection { return w.connector.(gobot.Connection) }
// Start initilizes i2c and reads from adaptor
// using specified interval to update with new value
func (w *WiichuckDriver) Start() (errs error) {
if err := w.connection.I2cStart(wiichuckAddress); err != nil {
func (w *WiichuckDriver) Start() (err error) {
bus := w.connector.I2cGetDefaultBus()
w.connection, err = w.connector.I2cGetConnection(wiichuckAddress, bus)
if err != nil {
return err
}
go func() {
for {
if err := w.connection.I2cWrite(wiichuckAddress, []byte{0x40, 0x00}); err != nil {
if _, err := w.connection.Write([]byte{0x40, 0x00}); err != nil {
w.Publish(w.Event(Error), err)
continue
}
time.Sleep(w.pauseTime)
if err := w.connection.I2cWrite(wiichuckAddress, []byte{0x00}); err != nil {
if _, err := w.connection.Write([]byte{0x00}); err != nil {
w.Publish(w.Event(Error), err)
continue
}
time.Sleep(w.pauseTime)
newValue, err := w.connection.I2cRead(wiichuckAddress, 6)
newValue := make([]byte, 6)
bytesRead, err := w.connection.Read(newValue)
if err != nil {
w.Publish(w.Event(Error), err)
continue
}
if len(newValue) == 6 {
if bytesRead == 6 {
if err = w.update(newValue); err != nil {
w.Publish(w.Event(Error), err)
continue

View File

@ -45,8 +45,9 @@ func TestWiichuckDriverStart(t *testing.T) {
sem := make(chan bool)
wii, adaptor := initTestWiichuckDriverWithStubbedAdaptor()
adaptor.i2cReadImpl = func() ([]byte, error) {
return []byte{1, 2, 3, 4, 5, 6}, nil
adaptor.i2cReadImpl = func(b []byte) (int, error) {
copy(b, []byte{1, 2, 3, 4, 5, 6})
return 6, nil
}
numberOfCyclesForEvery := 3

View File

@ -14,7 +14,7 @@ func main() {
blinkm := i2c.NewBlinkMDriver(beagleboneAdaptor)
work := func() {
gobot.Every(3*time.Second, func() {
gobot.Every(1*time.Second, func() {
r := byte(gobot.Rand(255))
g := byte(gobot.Rand(255))
b := byte(gobot.Rand(255))

View File

@ -0,0 +1,34 @@
package main
import (
"fmt"
"time"
"gobot.io/x/gobot"
"gobot.io/x/gobot/drivers/i2c"
"gobot.io/x/gobot/platforms/beaglebone"
)
func main() {
board := beaglebone.NewAdaptor()
accel := i2c.NewGroveAccelerometerDriver(board)
work := func() {
gobot.Every(500*time.Millisecond, func() {
if x, y, z, err := accel.XYZ(); err == nil {
fmt.Println(x, y, z)
fmt.Println(accel.Acceleration(x, y, z))
} else {
fmt.Println(err)
}
})
}
robot := gobot.NewRobot("accelBot",
[]gobot.Connection{board},
[]gobot.Device{accel},
work,
)
robot.Start()
}

34
examples/chip_blinkm.go Normal file
View File

@ -0,0 +1,34 @@
package main
import (
"fmt"
"time"
"gobot.io/x/gobot"
"gobot.io/x/gobot/drivers/i2c"
"gobot.io/x/gobot/platforms/chip"
)
func main() {
a := chip.NewAdaptor()
blinkm := i2c.NewBlinkMDriver(a)
work := func() {
gobot.Every(1*time.Second, func() {
r := byte(gobot.Rand(255))
g := byte(gobot.Rand(255))
b := byte(gobot.Rand(255))
blinkm.Rgb(r, g, b)
color, _ := blinkm.Color()
fmt.Println("color", color)
})
}
robot := gobot.NewRobot("blinkmBot",
[]gobot.Connection{a},
[]gobot.Device{blinkm},
work,
)
robot.Start()
}

View File

@ -14,7 +14,7 @@ func main() {
blinkm := i2c.NewBlinkMDriver(r)
work := func() {
gobot.Every(3*time.Second, func() {
gobot.Every(1*time.Second, func() {
r := byte(gobot.Rand(255))
g := byte(gobot.Rand(255))
b := byte(gobot.Rand(255))

View File

@ -12,6 +12,7 @@ import (
multierror "github.com/hashicorp/go-multierror"
"gobot.io/x/gobot"
"gobot.io/x/gobot/drivers/i2c"
"gobot.io/x/gobot/sysfs"
)
@ -25,7 +26,7 @@ type Adaptor struct {
kernel string
digitalPins []sysfs.DigitalPin
pwmPins map[string]*pwmPin
i2cDevice sysfs.I2cDevice
i2cBuses map[int]sysfs.I2cDevice
usrLed string
ocp string
analogPath string
@ -39,6 +40,7 @@ func NewAdaptor() *Adaptor {
name: gobot.DefaultName("Beaglebone"),
digitalPins: make([]sysfs.DigitalPin, 120),
pwmPins: make(map[string]*pwmPin),
i2cBuses: make(map[int]sysfs.I2cDevice),
}
b.setSlots()
@ -120,9 +122,11 @@ func (b *Adaptor) Finalize() (err error) {
}
}
}
if b.i2cDevice != nil {
if e := b.i2cDevice.Close(); e != nil {
err = multierror.Append(err, e)
for _, bus := range b.i2cBuses {
if bus != nil {
if e := bus.Close(); e != nil {
err = multierror.Append(err, e)
}
}
}
return
@ -195,31 +199,20 @@ func (b *Adaptor) AnalogRead(pin string) (val int, err error) {
return
}
// I2cStart starts a i2c device in specified address on i2c bus /dev/i2c-1
func (b *Adaptor) I2cStart(address int) (err error) {
if b.i2cDevice == nil {
b.i2cDevice, err = sysfs.NewI2cDevice("/dev/i2c-1", address)
// I2cGetConnection returns a connection to a device on a specified bus.
// Valid bus number is either 0 or 2 which corresponds to /dev/i2c-0 or /dev/i2c-2.
func (c *Adaptor) I2cGetConnection(address int, bus int) (connection i2c.I2cConnection, err error) {
if (bus != 0) && (bus != 2) {
return nil, fmt.Errorf("Bus number %d out of range", bus)
}
return
if c.i2cBuses[bus] == nil {
c.i2cBuses[bus], err = sysfs.NewI2cDevice(fmt.Sprintf("/dev/i2c-%d", bus))
}
return i2c.NewI2cConnection(c.i2cBuses[bus], address), err
}
// I2cWrite writes data to i2c device
func (b *Adaptor) I2cWrite(address int, data []byte) (err error) {
if err = b.i2cDevice.SetAddress(address); err != nil {
return
}
_, err = b.i2cDevice.Write(data)
return
}
// I2cRead returns size bytes from the i2c device
func (b *Adaptor) I2cRead(address int, size int) (data []byte, err error) {
if err = b.i2cDevice.SetAddress(address); err != nil {
return
}
data = make([]byte, size)
_, err = b.i2cDevice.Read(data)
return
func (c *Adaptor) I2cGetDefaultBus() int {
return 2
}
// translatePin converts digital pin name to pin position

View File

@ -21,7 +21,7 @@ var _ aio.AnalogReader = (*Adaptor)(nil)
var _ gpio.PwmWriter = (*Adaptor)(nil)
var _ gpio.ServoWriter = (*Adaptor)(nil)
var _ i2c.I2c = (*Adaptor)(nil)
var _ i2c.I2cConnector = (*Adaptor)(nil)
type NullReadWriteCloser struct {
contents []byte
@ -54,7 +54,7 @@ func TestBeagleboneAdaptor(t *testing.T) {
return make([]string, 2), nil
}
fs := sysfs.NewMockFilesystem([]string{
"/dev/i2c-1",
"/dev/i2c-2",
"/sys/devices/platform/bone_capemgr",
"/sys/devices/platform/ocp/ocp4",
"/sys/class/leds/beaglebone:green:usr1/brightness",
@ -139,12 +139,13 @@ func TestBeagleboneAdaptor(t *testing.T) {
// I2c
sysfs.SetSyscall(&sysfs.MockSyscall{})
a.I2cStart(0xff)
a.i2cDevice = &NullReadWriteCloser{}
con, err := a.I2cGetConnection(0xff, 2)
gobottest.Assert(t, err, nil)
a.I2cWrite(0xff, []byte{0x00, 0x01})
data, _ := a.I2cRead(0xff, 2)
con.Write([]byte{0x00, 0x01})
data := []byte{42, 42}
con.Read(data)
gobottest.Assert(t, data, []byte{0x00, 0x01})
gobottest.Assert(t, a.Finalize(), nil)

View File

@ -10,6 +10,7 @@ import (
multierror "github.com/hashicorp/go-multierror"
"gobot.io/x/gobot"
"gobot.io/x/gobot/drivers/i2c"
"gobot.io/x/gobot/sysfs"
)
@ -18,7 +19,7 @@ type Adaptor struct {
name string
digitalPins map[int]sysfs.DigitalPin
pinMap map[string]int
i2cDevice sysfs.I2cDevice
i2cBuses [3]sysfs.I2cDevice
}
var fixedPins = map[string]int{
@ -103,9 +104,11 @@ func (c *Adaptor) Finalize() (err error) {
}
}
}
if c.i2cDevice != nil {
if e := c.i2cDevice.Close(); e != nil {
err = multierror.Append(err, e)
for _, bus := range c.i2cBuses {
if bus != nil {
if e := bus.Close(); e != nil {
err = multierror.Append(err, e)
}
}
}
return
@ -171,33 +174,20 @@ func (c *Adaptor) DigitalWrite(pin string, val byte) (err error) {
return sysfsPin.Write(int(val))
}
// I2cStart starts an i2c device in specified address.
// This assumes that the bus used is /dev/i2c-1, which corresponds to
// pins labeled TWI1-SDA and TW1-SCK (pins 9 and 11 on header 13).
func (c *Adaptor) I2cStart(address int) (err error) {
if c.i2cDevice == nil {
c.i2cDevice, err = sysfs.NewI2cDevice("/dev/i2c-1", address)
// I2cGetConnection returns a connection to a device on a specified bus.
// Valid bus number is [0..2] which corresponds to /dev/i2c-0 through /dev/i2c-2.
func (c *Adaptor) I2cGetConnection(address int, bus int) (connection i2c.I2cConnection, err error) {
if (bus < 0) || (bus > 2) {
return nil, fmt.Errorf("Bus number %d out of range", bus)
}
return err
if c.i2cBuses[bus] == nil {
c.i2cBuses[bus], err = sysfs.NewI2cDevice(fmt.Sprintf("/dev/i2c-%d", bus))
}
return i2c.NewI2cConnection(c.i2cBuses[bus], address), err
}
// I2cWrite writes data to i2c device
func (c *Adaptor) I2cWrite(address int, data []byte) (err error) {
if err = c.i2cDevice.SetAddress(address); err != nil {
return
}
_, err = c.i2cDevice.Write(data)
return
}
// I2cRead returns value from i2c device using specified size
func (c *Adaptor) I2cRead(address int, size int) (data []byte, err error) {
if err = c.i2cDevice.SetAddress(address); err != nil {
return
}
data = make([]byte, size)
_, err = c.i2cDevice.Read(data)
return
func (c *Adaptor) I2cGetDefaultBus() int {
return 1
}
func getXIOBase() (baseAddr int, err error) {

View File

@ -16,7 +16,7 @@ var _ gobot.Adaptor = (*Adaptor)(nil)
var _ gpio.DigitalReader = (*Adaptor)(nil)
var _ gpio.DigitalWriter = (*Adaptor)(nil)
var _ i2c.I2c = (*Adaptor)(nil)
var _ i2c.I2cConnector = (*Adaptor)(nil)
type NullReadWriteCloser struct {
contents []byte
@ -80,11 +80,13 @@ func TestChipAdaptorI2c(t *testing.T) {
})
sysfs.SetFilesystem(fs)
sysfs.SetSyscall(&sysfs.MockSyscall{})
a.I2cStart(0xff)
a.i2cDevice = &NullReadWriteCloser{}
a.I2cWrite(0xff, []byte{0x00, 0x01})
data, _ := a.I2cRead(0xff, 2)
con, err := a.I2cGetConnection(0xff, 1)
gobottest.Assert(t, err, nil)
con.Write([]byte{0x00, 0x01})
data := []byte{42, 42}
con.Read(data)
gobottest.Assert(t, data, []byte{0x00, 0x01})
gobottest.Assert(t, a.Finalize(), nil)

View File

@ -1,12 +1,14 @@
package firmata
import (
"fmt"
"io"
"strconv"
"time"
"github.com/tarm/serial"
"gobot.io/x/gobot"
"gobot.io/x/gobot/drivers/i2c"
"gobot.io/x/gobot/platforms/firmata/client"
)
@ -23,7 +25,7 @@ type firmataBoard interface {
I2cWrite(int, []byte) error
I2cConfig(int) error
ServoConfig(int, int, int) error
Event(string) string
gobot.Eventer
}
// Adaptor is the Gobot Adaptor for Firmata based boards
@ -219,30 +221,16 @@ func (f *Adaptor) digitalPin(pin int) int {
return pin + 14
}
// I2cStart starts an i2c device at specified address
func (f *Adaptor) I2cStart(address int) (err error) {
return f.board.I2cConfig(0)
}
// I2cRead returns size bytes from the i2c device
// Returns an empty array if the response from the board has timed out
func (f *Adaptor) I2cRead(address int, size int) (data []byte, err error) {
ret := make(chan []byte)
if err = f.board.I2cRead(address, size); err != nil {
return
// I2cGetConnection returns a connection to a device on a specified bus.
// Only supports bus number 0
func (f *Adaptor) I2cGetConnection(address int, bus int) (connection i2c.I2cConnection, err error) {
if bus != 0 {
return nil, fmt.Errorf("Invalid bus number %d, only 0 is supported", bus)
}
f.Once(f.board.Event("I2cReply"), func(data interface{}) {
ret <- data.(client.I2cReply).Data
})
data = <-ret
return
err = f.board.I2cConfig(0)
return NewFirmataI2cConnection(f, address), err
}
// I2cWrite writes data to i2c device
func (f *Adaptor) I2cWrite(address int, data []byte) (err error) {
return f.board.I2cWrite(address, data)
func (c *Adaptor) I2cGetDefaultBus() int {
return 0
}

View File

@ -25,7 +25,7 @@ var _ aio.AnalogReader = (*Adaptor)(nil)
var _ gpio.PwmWriter = (*Adaptor)(nil)
var _ gpio.ServoWriter = (*Adaptor)(nil)
var _ i2c.I2c = (*Adaptor)(nil)
var _ i2c.I2cConnector = (*Adaptor)(nil)
type readWriteCloser struct{}
@ -165,8 +165,9 @@ func TestAdaptorAnalogRead(t *testing.T) {
func TestAdaptorI2cStart(t *testing.T) {
a := initTestAdaptor()
a.I2cStart(0x00)
a.I2cGetConnection(0, 0)
}
func TestAdaptorI2cRead(t *testing.T) {
a := initTestAdaptor()
i := []byte{100}
@ -175,13 +176,21 @@ func TestAdaptorI2cRead(t *testing.T) {
<-time.After(10 * time.Millisecond)
a.Publish(a.board.Event("I2cReply"), i2cReply)
}()
data, err := a.I2cRead(0x00, 1)
con, err := a.I2cGetConnection(0, 0)
gobottest.Assert(t, err, nil)
gobottest.Assert(t, data, i)
response := []byte{12}
_, err = con.Read(response)
gobottest.Assert(t, err, nil)
gobottest.Assert(t, response, i)
}
func TestAdaptorI2cWrite(t *testing.T) {
a := initTestAdaptor()
a.I2cWrite(0x00, []byte{0x00, 0x01})
con, err := a.I2cGetConnection(0, 0)
gobottest.Assert(t, err, nil)
con.Write([]byte{0x00, 0x01})
}
func TestServoConfig(t *testing.T) {

View File

@ -0,0 +1,126 @@
package firmata
import (
// "gobot.io/x/gobot/drivers/i2c"
"gobot.io/x/gobot/platforms/firmata/client"
)
type firmataI2cConnection struct {
address int
adaptor *Adaptor
}
// NewFirmataI2cConnection creates an I2C connection to an I2C device at
// the specified address
func NewFirmataI2cConnection(adaptor *Adaptor, address int) (connection *firmataI2cConnection) {
return &firmataI2cConnection{adaptor: adaptor, address: address}
}
// Read tries to read a full buffer from the i2c device.
// Returns an empty array if the response from the board has timed out.
func (c *firmataI2cConnection) Read(b []byte) (read int, err error) {
ret := make(chan []byte)
if err = c.adaptor.board.I2cRead(c.address, len(b)); err != nil {
return
}
c.adaptor.board.Once(c.adaptor.board.Event("I2cReply"), func(data interface{}) {
ret <- data.(client.I2cReply).Data
})
result := <-ret
copy(b, result)
read = len(result)
return
}
func (c *firmataI2cConnection) Write(data []byte) (written int, err error) {
err = c.adaptor.board.I2cWrite(c.address, data)
// Assume successful write of whole buffer
written = len(data)
return
}
func (c *firmataI2cConnection) Close() error {
return nil
}
func (c *firmataI2cConnection) ReadByte() (val uint8, err error) {
buf := []byte{0}
if _, err = c.Read(buf); err != nil {
return
}
val = buf[0]
return
}
func (c *firmataI2cConnection) ReadByteData(reg uint8) (val uint8, err error) {
if err = c.WriteByte(reg); err != nil {
return
}
return c.ReadByte()
}
func (c *firmataI2cConnection) ReadWordData(reg uint8) (val uint16, err error) {
if err = c.WriteByte(reg); err != nil {
return
}
buf := []byte{0, 0}
if _, err = c.Read(buf); err != nil {
return
}
low, high := buf[0], buf[1]
val = (uint16(high) << 8) | uint16(low)
return
}
func (c *firmataI2cConnection) ReadBlockData(reg uint8, b []byte) (n int, err error) {
// Assume target device handles this well, will not behave exactly as on SMBus
if err = c.WriteByte(reg); err != nil {
return
}
// Try to read full 32 bytes
buf := make([]byte, 32)
bytesRead, err := c.Read(buf)
copy(b, buf)
return bytesRead, err
}
func (c *firmataI2cConnection) WriteByte(val uint8) (err error) {
buf := []byte{val}
_, err = c.Write(buf)
return
}
func (c *firmataI2cConnection) WriteByteData(reg uint8, val uint8) (err error) {
buf := []byte{reg, val}
_, err = c.Write(buf)
return
}
func (c *firmataI2cConnection) WriteWordData(reg uint8, val uint16) (err error) {
low := uint8(val & 0xff)
high := uint8((val >> 8) & 0xff)
buf := []byte{reg, low, high}
_, err = c.Write(buf)
return
}
func (c *firmataI2cConnection) WriteBlockData(reg uint8, data []byte) (err error) {
if len(data) > 32 {
data = data[:32]
}
buf := make([]byte, len(data)+1)
copy(buf[:1], data)
buf[0] = reg
_, err = c.Write(buf)
return
}

View File

@ -2,11 +2,13 @@ package edison
import (
"errors"
"fmt"
"os"
"strconv"
multierror "github.com/hashicorp/go-multierror"
"gobot.io/x/gobot"
"gobot.io/x/gobot/drivers/i2c"
"gobot.io/x/gobot/sysfs"
)
@ -56,7 +58,7 @@ type Adaptor struct {
tristate sysfs.DigitalPin
digitalPins map[int]sysfs.DigitalPin
pwmPins map[int]*pwmPin
i2cDevice sysfs.I2cDevice
i2cBus sysfs.I2cDevice
connect func(e *Adaptor) (err error)
}
@ -140,8 +142,8 @@ func (e *Adaptor) Finalize() (err error) {
}
}
}
if e.i2cDevice != nil {
if errs := e.i2cDevice.Close(); errs != nil {
if e.i2cBus != nil {
if errs := e.i2cBus.Close(); errs != nil {
err = multierror.Append(err, errs)
}
}
@ -421,40 +423,27 @@ func (e *Adaptor) AnalogRead(pin string) (val int, err error) {
return val / 4, err
}
// I2cStart initializes i2c device for addresss
func (e *Adaptor) I2cStart(address int) (err error) {
if e.i2cDevice != nil {
return
// I2cGetConnection returns a connection to a device on a specified bus.
// Valid bus numbers are 1 and 6 (arduino).
func (e *Adaptor) I2cGetConnection(address int, bus int) (connection i2c.I2cConnection, err error) {
if !(bus == e.I2cGetDefaultBus()) {
return nil, errors.New("Unsupported I2C bus")
}
if e.i2cBus == nil {
if bus == 6 && e.board == "arduino" {
e.arduinoI2CSetup()
}
e.i2cBus, err = sysfs.NewI2cDevice(fmt.Sprintf("/dev/i2c-%d", bus))
}
return i2c.NewI2cConnection(e.i2cBus, address), err
}
// most board use I2C bus 1
bus := "/dev/i2c-1"
// except for Arduino which uses bus 6
func (e *Adaptor) I2cGetDefaultBus() int {
// Arduino uses bus 6
if e.board == "arduino" {
bus = "/dev/i2c-6"
e.arduinoI2CSetup()
return 6
} else {
// all other default to 1
return 1
}
e.i2cDevice, err = sysfs.NewI2cDevice(bus, address)
return
}
// I2cWrite writes data to i2c device
func (e *Adaptor) I2cWrite(address int, data []byte) (err error) {
if err = e.i2cDevice.SetAddress(address); err != nil {
return err
}
_, err = e.i2cDevice.Write(data)
return
}
// I2cRead returns size bytes from the i2c device
func (e *Adaptor) I2cRead(address int, size int) (data []byte, err error) {
data = make([]byte, size)
if err = e.i2cDevice.SetAddress(address); err != nil {
return
}
_, err = e.i2cDevice.Read(data)
return
}

View File

@ -19,7 +19,7 @@ var _ gpio.DigitalWriter = (*Adaptor)(nil)
var _ aio.AnalogReader = (*Adaptor)(nil)
var _ gpio.PwmWriter = (*Adaptor)(nil)
var _ i2c.I2c = (*Adaptor)(nil)
var _ i2c.I2cConnector = (*Adaptor)(nil)
type NullReadWriteCloser struct {
contents []byte
@ -139,7 +139,7 @@ func TestAdaptorFinalize(t *testing.T) {
a.PwmWrite("5", 100)
sysfs.SetSyscall(&sysfs.MockSyscall{})
a.I2cStart(0xff)
a.I2cGetConnection(0xff, 6)
gobottest.Assert(t, a.Finalize(), nil)
@ -164,12 +164,12 @@ func TestAdaptorI2c(t *testing.T) {
a, _ := initTestAdaptor()
sysfs.SetSyscall(&sysfs.MockSyscall{})
a.I2cStart(0xff)
con, err := a.I2cGetConnection(0xff, 6)
gobottest.Assert(t, err, nil)
a.i2cDevice = &NullReadWriteCloser{}
a.I2cWrite(0xff, []byte{0x00, 0x01})
data, _ := a.I2cRead(0xff, 2)
con.Write([]byte{0x00, 0x01})
data := []byte{42, 42}
con.Read(data)
gobottest.Assert(t, data, []byte{0x00, 0x01})
}

View File

@ -1,116 +1,116 @@
package edison
var sparkfunPinMap = map[string]sysfsPin{
"12": sysfsPin{
pin: 12,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"13": sysfsPin{
pin: 13,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"14": sysfsPin{
pin: 14,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"15": sysfsPin{
pin: 15,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"44": sysfsPin{
pin: 44,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"45": sysfsPin{
pin: 45,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"46": sysfsPin{
pin: 46,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"47": sysfsPin{
pin: 47,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"48": sysfsPin{
pin: 48,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"49": sysfsPin{
pin: 49,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"128": sysfsPin{
pin: 128,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"129": sysfsPin{
pin: 129,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"130": sysfsPin{
pin: 130,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"131": sysfsPin{
pin: 131,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"182": sysfsPin{
pin: 182,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"183": sysfsPin{
pin: 183,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
}
"12": sysfsPin{
pin: 12,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"13": sysfsPin{
pin: 13,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"14": sysfsPin{
pin: 14,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"15": sysfsPin{
pin: 15,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"44": sysfsPin{
pin: 44,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"45": sysfsPin{
pin: 45,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"46": sysfsPin{
pin: 46,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"47": sysfsPin{
pin: 47,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"48": sysfsPin{
pin: 48,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"49": sysfsPin{
pin: 49,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"128": sysfsPin{
pin: 128,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"129": sysfsPin{
pin: 129,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"130": sysfsPin{
pin: 130,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"131": sysfsPin{
pin: 131,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"182": sysfsPin{
pin: 182,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
"183": sysfsPin{
pin: 183,
resistor: -1,
levelShifter: -1,
pwmPin: -1,
mux: []mux{},
},
}

View File

@ -2,11 +2,13 @@ package joule
import (
"errors"
"fmt"
"os"
"strconv"
multierror "github.com/hashicorp/go-multierror"
"gobot.io/x/gobot"
"gobot.io/x/gobot/drivers/i2c"
"gobot.io/x/gobot/sysfs"
)
@ -46,7 +48,7 @@ type Adaptor struct {
name string
digitalPins map[int]sysfs.DigitalPin
pwmPins map[int]*pwmPin
i2cDevice sysfs.I2cDevice
i2cBuses [3]sysfs.I2cDevice
connect func(e *Adaptor) (err error)
}
@ -93,9 +95,11 @@ func (e *Adaptor) Finalize() (err error) {
}
}
}
if e.i2cDevice != nil {
if errs := e.i2cDevice.Close(); errs != nil {
err = multierror.Append(err, errs)
for _, bus := range e.i2cBuses {
if bus != nil {
if errs := bus.Close(); errs != nil {
err = multierror.Append(err, errs)
}
}
}
return
@ -172,32 +176,18 @@ func (e *Adaptor) PwmWrite(pin string, val byte) (err error) {
return errors.New("Not a PWM pin")
}
// I2cStart initializes i2c device for addresss
func (e *Adaptor) I2cStart(address int) (err error) {
if e.i2cDevice != nil {
return
// I2cGetConnection returns a connection to a device on a specified bus.
// Valid bus number is [0..2] which corresponds to /dev/i2c-0 through /dev/i2c-2.
func (c *Adaptor) I2cGetConnection(address int, bus int) (connection i2c.I2cConnection, err error) {
if (bus < 0) || (bus > 2) {
return nil, fmt.Errorf("Bus number %d out of range", bus)
}
// TODO: handle the additional I2C buses
e.i2cDevice, err = sysfs.NewI2cDevice("/dev/i2c-0", address)
return
if c.i2cBuses[bus] == nil {
c.i2cBuses[bus], err = sysfs.NewI2cDevice(fmt.Sprintf("/dev/i2c-%d", bus))
}
return i2c.NewI2cConnection(c.i2cBuses[bus], address), err
}
// I2cWrite writes data to i2c device
func (e *Adaptor) I2cWrite(address int, data []byte) (err error) {
if err = e.i2cDevice.SetAddress(address); err != nil {
return err
}
_, err = e.i2cDevice.Write(data)
return
}
// I2cRead returns size bytes from the i2c device
func (e *Adaptor) I2cRead(address int, size int) (data []byte, err error) {
data = make([]byte, size)
if err = e.i2cDevice.SetAddress(address); err != nil {
return
}
_, err = e.i2cDevice.Read(data)
return
func (c *Adaptor) I2cGetDefaultBus() int {
return 0
}

View File

@ -17,7 +17,7 @@ var _ gpio.DigitalReader = (*Adaptor)(nil)
var _ gpio.DigitalWriter = (*Adaptor)(nil)
var _ gpio.PwmWriter = (*Adaptor)(nil)
var _ i2c.I2c = (*Adaptor)(nil)
var _ i2c.I2cConnector = (*Adaptor)(nil)
type NullReadWriteCloser struct {
contents []byte
@ -126,7 +126,7 @@ func TestAdaptorFinalize(t *testing.T) {
a.PwmWrite("25", 100)
sysfs.SetSyscall(&sysfs.MockSyscall{})
a.I2cStart(0xff)
a.I2cGetConnection(0xff, 0)
gobottest.Assert(t, a.Finalize(), nil)
@ -151,12 +151,12 @@ func TestAdaptorI2c(t *testing.T) {
a, _ := initTestAdaptor()
sysfs.SetSyscall(&sysfs.MockSyscall{})
a.I2cStart(0xff)
con, err := a.I2cGetConnection(0xff, 0)
gobottest.Assert(t, err, nil)
a.i2cDevice = &NullReadWriteCloser{}
a.I2cWrite(0xff, []byte{0x00, 0x01})
data, _ := a.I2cRead(0xff, 2)
con.Write([]byte{0x00, 0x01})
data := []byte{42, 42}
con.Read(data)
gobottest.Assert(t, data, []byte{0x00, 0x01})
}

View File

@ -10,6 +10,7 @@ import (
multierror "github.com/hashicorp/go-multierror"
"gobot.io/x/gobot"
"gobot.io/x/gobot/drivers/i2c"
"gobot.io/x/gobot/sysfs"
)
@ -19,12 +20,12 @@ var readFile = func() ([]byte, error) {
// Adaptor is the Gobot Adaptor for the Raspberry Pi
type Adaptor struct {
name string
revision string
i2cLocation string
digitalPins map[int]sysfs.DigitalPin
pwmPins []int
i2cDevice sysfs.I2cDevice
name string
revision string
digitalPins map[int]sysfs.DigitalPin
pwmPins []int
i2cDefaultBus int
i2cBuses [2]sysfs.I2cDevice
}
// NewAdaptor creates a Raspi Adaptor
@ -39,10 +40,10 @@ func NewAdaptor() *Adaptor {
if strings.Contains(v, "Revision") {
s := strings.Split(string(v), " ")
version, _ := strconv.ParseInt("0x"+s[len(s)-1], 0, 64)
r.i2cLocation = "/dev/i2c-1"
r.i2cDefaultBus = 1
if version <= 3 {
r.revision = "1"
r.i2cLocation = "/dev/i2c-0"
r.i2cDefaultBus = 0
} else if version <= 15 {
r.revision = "2"
} else {
@ -80,9 +81,11 @@ func (r *Adaptor) Finalize() (err error) {
err = multierror.Append(err, perr)
}
}
if r.i2cDevice != nil {
if perr := r.i2cDevice.Close(); err != nil {
err = multierror.Append(err, perr)
for _, bus := range r.i2cBuses {
if bus != nil {
if e := bus.Close(); e != nil {
err = multierror.Append(err, e)
}
}
}
return
@ -161,31 +164,20 @@ func (r *Adaptor) DigitalWrite(pin string, val byte) (err error) {
return sysfsPin.Write(int(val))
}
// I2cStart starts a i2c device in specified address
func (r *Adaptor) I2cStart(address int) (err error) {
if r.i2cDevice == nil {
r.i2cDevice, err = sysfs.NewI2cDevice(r.i2cLocation, address)
// I2cGetConnection returns a connection to a device on a specified bus.
// Valid bus number is [0..1] which corresponds to /dev/i2c-0 through /dev/i2c-1.
func (c *Adaptor) I2cGetConnection(address int, bus int) (connection i2c.I2cConnection, err error) {
if (bus < 0) || (bus > 1) {
return nil, fmt.Errorf("Bus number %d out of range", bus)
}
return err
if c.i2cBuses[bus] == nil {
c.i2cBuses[bus], err = sysfs.NewI2cDevice(fmt.Sprintf("/dev/i2c-%d", bus))
}
return i2c.NewI2cConnection(c.i2cBuses[bus], address), err
}
// I2CWrite writes data to i2c device
func (r *Adaptor) I2cWrite(address int, data []byte) (err error) {
if err = r.i2cDevice.SetAddress(address); err != nil {
return
}
_, err = r.i2cDevice.Write(data)
return
}
// I2cRead returns value from i2c device using specified size
func (r *Adaptor) I2cRead(address int, size int) (data []byte, err error) {
if err = r.i2cDevice.SetAddress(address); err != nil {
return
}
data = make([]byte, size)
_, err = r.i2cDevice.Read(data)
return
func (c *Adaptor) I2cGetDefaultBus() int {
return c.i2cDefaultBus
}
// PwmWrite writes a PWM signal to the specified pin

View File

@ -16,7 +16,7 @@ var _ gobot.Adaptor = (*Adaptor)(nil)
var _ gpio.DigitalReader = (*Adaptor)(nil)
var _ gpio.DigitalWriter = (*Adaptor)(nil)
var _ i2c.I2c = (*Adaptor)(nil)
var _ i2c.I2cConnector = (*Adaptor)(nil)
type NullReadWriteCloser struct {
contents []byte
@ -67,7 +67,7 @@ Serial : 000000003bc748ea
}
a := NewAdaptor()
gobottest.Assert(t, a.Name(), "RaspberryPi")
gobottest.Assert(t, a.i2cLocation, "/dev/i2c-1")
gobottest.Assert(t, a.i2cDefaultBus, 1)
gobottest.Assert(t, a.revision, "3")
readFile = func() ([]byte, error) {
@ -78,7 +78,7 @@ Serial : 000000003bc748ea
`), nil
}
a = NewAdaptor()
gobottest.Assert(t, a.i2cLocation, "/dev/i2c-1")
gobottest.Assert(t, a.i2cDefaultBus, 1)
gobottest.Assert(t, a.revision, "2")
readFile = func() ([]byte, error) {
@ -89,7 +89,7 @@ Serial : 000000003bc748ea
`), nil
}
a = NewAdaptor()
gobottest.Assert(t, a.i2cLocation, "/dev/i2c-0")
gobottest.Assert(t, a.i2cDefaultBus, 0)
gobottest.Assert(t, a.revision, "1")
}
@ -110,7 +110,7 @@ func TestAdaptorFinalize(t *testing.T) {
a.DigitalWrite("3", 1)
a.PwmWrite("7", 255)
a.I2cStart(0xff)
a.I2cGetConnection(0xff, 0)
gobottest.Assert(t, a.Finalize(), nil)
}
@ -161,10 +161,12 @@ func TestAdaptorI2c(t *testing.T) {
})
sysfs.SetFilesystem(fs)
sysfs.SetSyscall(&sysfs.MockSyscall{})
a.I2cStart(0xff)
a.i2cDevice = &NullReadWriteCloser{}
a.I2cWrite(0xff, []byte{0x00, 0x01})
data, _ := a.I2cRead(0xff, 2)
con, err := a.I2cGetConnection(0xff, 1)
gobottest.Assert(t, err, nil)
con.Write([]byte{0x00, 0x01})
data := []byte{42, 42}
con.Read(data)
gobottest.Assert(t, data, []byte{0x00, 0x01})
}

View File

@ -9,16 +9,28 @@ import (
)
const (
I2C_SLAVE = 0x0703
I2C_SMBUS = 0x0720
I2C_SMBUS_WRITE = 0
I2C_SMBUS_READ = 1
I2C_SMBUS_I2C_BLOCK_DATA = 8
// ioctl signals
I2C_SLAVE = 0x0703
I2C_FUNCS = 0x0705
I2C_SMBUS = 0x0720
// Read/write markers
I2C_SMBUS_READ = 1
I2C_SMBUS_WRITE = 0
// Adapter functionality
I2C_FUNCS = 0x0705
I2C_FUNC_SMBUS_READ_BLOCK_DATA = 0x01000000
I2C_FUNC_SMBUS_WRITE_BLOCK_DATA = 0x02000000
// Transaction types
I2C_SMBUS_BYTE = 1
I2C_SMBUS_BYTE_DATA = 2
I2C_SMBUS_WORD_DATA = 3
I2C_SMBUS_PROC_CALL = 4
I2C_SMBUS_BLOCK_DATA = 5
I2C_SMBUS_I2C_BLOCK_DATA = 6
I2C_SMBUS_BLOCK_PROC_CALL = 7 /* SMBus 2.0 */
I2C_SMBUS_BLOCK_DATA_PEC = 8 /* SMBus 2.0 */
I2C_SMBUS_PROC_CALL_PEC = 9 /* SMBus 2.0 */
I2C_SMBUS_BLOCK_PROC_CALL_PEC = 10 /* SMBus 2.0 */
I2C_SMBUS_WORD_DATA_PEC = 11 /* SMBus 2.0 */
)
type i2cSmbusIoctlData struct {
@ -28,9 +40,21 @@ type i2cSmbusIoctlData struct {
data uintptr
}
type I2cOperations interface {
io.ReadWriteCloser
ReadByte() (val uint8, err error)
ReadByteData(reg uint8) (val uint8, err error)
ReadWordData(reg uint8) (val uint16, err error)
ReadBlockData(reg uint8, b []byte) (n int, err error)
WriteByte(val uint8) (err error)
WriteByteData(reg uint8, val uint8) (err error)
WriteWordData(reg uint8, val uint16) (err error)
WriteBlockData(reg uint8, b []byte) (err error)
}
// I2cDevice is the interface to a specific i2c bus
type I2cDevice interface {
io.ReadWriteCloser
I2cOperations
SetAddress(int) error
}
@ -40,8 +64,8 @@ type i2cDevice struct {
}
// NewI2cDevice returns an io.ReadWriteCloser with the proper ioctrl given
// an i2c bus location and device address
func NewI2cDevice(location string, address int) (d *i2cDevice, err error) {
// an i2c bus location.
func NewI2cDevice(location string) (d *i2cDevice, err error) {
d = &i2cDevice{}
if d.file, err = OpenFile(location, os.O_RDWR, os.ModeExclusive); err != nil {
@ -51,8 +75,6 @@ func NewI2cDevice(location string, address int) (d *i2cDevice, err error) {
return
}
err = d.SetAddress(address)
return
}
@ -89,63 +111,88 @@ func (d *i2cDevice) Close() (err error) {
return d.file.Close()
}
func (d *i2cDevice) Read(b []byte) (n int, err error) {
func (d *i2cDevice) ReadByte() (val uint8, err error) {
var data uint8
err = d.smbusAccess(I2C_SMBUS_READ, 0, I2C_SMBUS_BYTE, uintptr(unsafe.Pointer(&data)))
return data, err
}
func (d *i2cDevice) ReadByteData(reg uint8) (val uint8, err error) {
var data uint8
err = d.smbusAccess(I2C_SMBUS_READ, reg, I2C_SMBUS_BYTE_DATA, uintptr(unsafe.Pointer(&data)))
return data, err
}
func (d *i2cDevice) ReadWordData(reg uint8) (val uint16, err error) {
var data uint16
err = d.smbusAccess(I2C_SMBUS_READ, reg, I2C_SMBUS_WORD_DATA, uintptr(unsafe.Pointer(&data)))
return data, err
}
func (d *i2cDevice) ReadBlockData(reg uint8, buf []byte) (n int, err error) {
if d.funcs&I2C_FUNC_SMBUS_READ_BLOCK_DATA == 0 {
// Adapter doesn't support SMBus block read
return d.file.Read(b)
return 0, fmt.Errorf("SMBus block data reading not supported")
}
// Command byte - a data byte which often selects a register on the device:
// https://www.kernel.org/doc/Documentation/i2c/smbus-protocol
command := byte(b[0])
buf := b[1:]
data := make([]byte, len(buf)+1)
data[0] = byte(len(buf))
copy(data[1:], buf)
data := make([]byte, 32+1) // Max message + size as defined by SMBus standard
smbus := &i2cSmbusIoctlData{
readWrite: I2C_SMBUS_READ,
command: command,
size: I2C_SMBUS_I2C_BLOCK_DATA,
data: uintptr(unsafe.Pointer(&data[0])),
}
_, _, errno := Syscall(
syscall.SYS_IOCTL,
d.file.Fd(),
I2C_SMBUS,
uintptr(unsafe.Pointer(smbus)),
)
err = d.smbusAccess(I2C_SMBUS_READ, reg, I2C_SMBUS_I2C_BLOCK_DATA, uintptr(unsafe.Pointer(&data[0])))
if errno != 0 {
return n, fmt.Errorf("Read failed with syscall.Errno %v", errno)
}
copy(b, data[1:])
return int(data[0]), nil
copy(buf, data[1:])
return int(data[0]), err
}
func (d *i2cDevice) Write(b []byte) (n int, err error) {
func (d *i2cDevice) WriteByte(val uint8) (err error) {
err = d.smbusAccess(I2C_SMBUS_WRITE, val, I2C_SMBUS_BYTE, uintptr(0))
return err
}
func (d *i2cDevice) WriteByteData(reg uint8, val uint8) (err error) {
var data = val
err = d.smbusAccess(I2C_SMBUS_WRITE, reg, I2C_SMBUS_BYTE_DATA, uintptr(unsafe.Pointer(&data)))
return err
}
func (d *i2cDevice) WriteWordData(reg uint8, val uint16) (err error) {
var data = val
err = d.smbusAccess(I2C_SMBUS_WRITE, reg, I2C_SMBUS_WORD_DATA, uintptr(unsafe.Pointer(&data)))
return err
}
func (d *i2cDevice) WriteBlockData(reg uint8, data []byte) (err error) {
if d.funcs&I2C_FUNC_SMBUS_WRITE_BLOCK_DATA == 0 {
// Adapter doesn't support SMBus block write
return d.file.Write(b)
return fmt.Errorf("SMBus block data writing not supported")
}
// Command byte - a data byte which often selects a register on the device:
// https://www.kernel.org/doc/Documentation/i2c/smbus-protocol
command := byte(b[0])
buf := b[1:]
if len(data) > 32 {
data = data[:32]
}
data := make([]byte, len(buf)+1)
data[0] = byte(len(buf))
buf := make([]byte, len(data)+1)
copy(buf[:1], data)
buf[0] = uint8(len(data))
copy(data[1:], buf)
err = d.smbusAccess(I2C_SMBUS_WRITE, reg, I2C_SMBUS_I2C_BLOCK_DATA, uintptr(unsafe.Pointer(&buf[0])))
return err
}
// Read implements the io.ReadWriteCloser method by direct I2C read operations.
func (d *i2cDevice) Read(b []byte) (n int, err error) {
return d.file.Read(b)
}
// Write implements the io.ReadWriteCloser method by direct I2C write operations.
func (d *i2cDevice) Write(b []byte) (n int, err error) {
return d.file.Write(b)
}
func (d *i2cDevice) smbusAccess(readWrite byte, command byte, size uint32, data uintptr) error {
smbus := &i2cSmbusIoctlData{
readWrite: I2C_SMBUS_WRITE,
readWrite: readWrite,
command: command,
size: I2C_SMBUS_I2C_BLOCK_DATA,
data: uintptr(unsafe.Pointer(&data[0])),
size: size,
data: data,
}
_, _, errno := Syscall(
@ -156,8 +203,8 @@ func (d *i2cDevice) Write(b []byte) (n int, err error) {
)
if errno != 0 {
err = fmt.Errorf("Write failed with syscall.Errno %v", errno)
return fmt.Errorf("Failed with syscall.Errno %v", errno)
}
return len(b), err
return nil
}

View File

@ -11,7 +11,7 @@ func TestNewI2cDevice(t *testing.T) {
fs := NewMockFilesystem([]string{})
SetFilesystem(fs)
i, err := NewI2cDevice(os.DevNull, 0xff)
i, err := NewI2cDevice(os.DevNull)
gobottest.Refute(t, err, nil)
fs = NewMockFilesystem([]string{
@ -20,12 +20,12 @@ func TestNewI2cDevice(t *testing.T) {
SetFilesystem(fs)
i, err = NewI2cDevice("/dev/i2c-1", 0xff)
i, err = NewI2cDevice("/dev/i2c-1")
gobottest.Refute(t, err, nil)
SetSyscall(&MockSyscall{})
i, err = NewI2cDevice("/dev/i2c-1", 0xff)
i, err = NewI2cDevice("/dev/i2c-1")
var _ I2cDevice = i
gobottest.Assert(t, err, nil)