1
0
mirror of https://github.com/hybridgroup/gobot.git synced 2025-04-24 13:48:49 +08:00

i2c/spi: remove offensive terminology

This commit is contained in:
Thomas Kohler 2024-02-13 18:02:34 +01:00
parent c159228f48
commit baafed367c
28 changed files with 74 additions and 74 deletions

View File

@ -37,7 +37,7 @@ func getSyscallFuncImpl(
system.I2C_FUNC_SMBUS_WRITE_WORD_DATA
}
// set address
if (trap == system.Syscall_SYS_IOCTL) && (a2 == system.I2C_SLAVE) {
if (trap == system.Syscall_SYS_IOCTL) && (a2 == system.I2C_TARGET) {
if errorMask&0x02 == 0x02 {
return 0, 0, 1
}

View File

@ -19,17 +19,17 @@ import (
// Wiring
// PWR Tinkerboard: 1 (+3.3V, VCC), 2(+5V), 6, 9, 14, 20 (GND)
// GPIO-SPI Tinkerboard (same as SPI2): 23 (CLK), 19 (TXD), 21 (RXD), 24 (CSN0)
// MFRC522 plate: VCC, GND, SCK (CLK), MOSI (->TXD), MISO (->RXD), NSS/SDA (CSN0/CSN1?)
// MFRC522 plate: VCC, GND, SCK (CLK), SDO (->TXD), SDI (->RXD), NCS/SDA (CSN0/CSN1?)
const (
sclk = "23"
nss = "24"
mosi = "19"
miso = "21"
ncs = "24"
sdo = "19"
sdi = "21"
speedHz = 5000 // more than 15kHz is not possible with GPIO's, so we choose 5kHz
)
func main() {
a := tinkerboard.NewAdaptor(adaptors.WithSpiGpioAccess(sclk, nss, mosi, miso))
a := tinkerboard.NewAdaptor(adaptors.WithSpiGpioAccess(sclk, ncs, sdo, sdi))
d := spi.NewMFRC522Driver(a, spi.WithSpeed(speedHz))
wasCardDetected := false

View File

@ -19,7 +19,7 @@ import (
// PWR Tinkerboard: 1 (+3.3V, VCC), 2(+5V), 6, 9, 14, 20 (GND)
// SPI0 Tinkerboard (not working with armbian): 11 (CLK), 13 (TXD), 15 (RXD), 29 (CSN0), 31 (CSN1, n.c.)
// SPI2 Tinkerboard: 23 (CLK), 19 (TXD), 21 (RXD), 24 (CSN0), 26 (CSN1, n.c.)
// MFRC522 plate: VCC, GND, SCK (CLK), MOSI (->TXD), MISO (->RXD), NSS/SDA (CSN0/CSN1?)
// MFRC522 plate: VCC, GND, SCK (CLK), SDO (->TXD), SDI (->RXD), NCS/SDA (CSN0/CSN1?)
func main() {
a := tinkerboard.NewAdaptor()
d := spi.NewMFRC522Driver(a, spi.WithBusNumber(2))

View File

@ -63,9 +63,9 @@ func WithGpiodAccess() func(DigitalPinsOptioner) {
}
// WithSpiGpioAccess can be used to switch the default SPI implementation to GPIO usage.
func WithSpiGpioAccess(sclkPin, nssPin, mosiPin, misoPin string) func(DigitalPinsOptioner) {
func WithSpiGpioAccess(sclkPin, ncsPin, sdoPin, sdiPin string) func(DigitalPinsOptioner) {
return func(o DigitalPinsOptioner) {
o.setDigitalPinsForSystemSpi(sclkPin, nssPin, mosiPin, misoPin)
o.setDigitalPinsForSystemSpi(sclkPin, ncsPin, sdoPin, sdiPin)
}
}

View File

@ -13,7 +13,7 @@ import (
type DigitalPinsOptioner interface {
setDigitalPinInitializer(initializer digitalPinInitializer)
setDigitalPinsForSystemGpiod()
setDigitalPinsForSystemSpi(sclkPin, nssPin, mosiPin, misoPin string)
setDigitalPinsForSystemSpi(sclkPin, ncsPin, sdoPin, sdiPin string)
prepareDigitalPinsActiveLow(pin string, otherPins ...string)
prepareDigitalPinsPullDown(pin string, otherPins ...string)
prepareDigitalPinsPullUp(pin string, otherPins ...string)
@ -37,8 +37,8 @@ func (a *DigitalPinsAdaptor) setDigitalPinsForSystemGpiod() {
system.WithDigitalPinGpiodAccess()(a.sys)
}
func (a *DigitalPinsAdaptor) setDigitalPinsForSystemSpi(sclkPin, nssPin, mosiPin, misoPin string) {
system.WithSpiGpioAccess(a, sclkPin, nssPin, mosiPin, misoPin)(a.sys)
func (a *DigitalPinsAdaptor) setDigitalPinsForSystemSpi(sclkPin, ncsPin, sdoPin, sdiPin string) {
system.WithSpiGpioAccess(a, sclkPin, ncsPin, sdoPin, sdiPin)(a.sys)
}
func (a *DigitalPinsAdaptor) prepareDigitalPinsActiveLow(id string, otherIDs ...string) {

View File

@ -60,7 +60,7 @@ type Adaptor struct {
// Optional parameters:
//
// adaptors.WithGpiodAccess(): use character device gpiod driver instead of sysfs
// adaptors.WithSpiGpioAccess(sclk, nss, mosi, miso): use GPIO's instead of /dev/spidev#.#
// adaptors.WithSpiGpioAccess(sclk, ncs, sdo, sdi): use GPIO's instead of /dev/spidev#.#
//
// Optional parameters for PWM, see [adaptors.NewPWMPinsAdaptor]
func NewAdaptor(opts ...interface{}) *Adaptor {

View File

@ -16,7 +16,7 @@ type PocketBeagleAdaptor struct {
// Optional parameters:
//
// adaptors.WithGpiodAccess(): use character device gpiod driver instead of sysfs
// adaptors.WithSpiGpioAccess(sclk, nss, mosi, miso): use GPIO's instead of /dev/spidev#.#
// adaptors.WithSpiGpioAccess(sclk, ncs, sdo, sdi): use GPIO's instead of /dev/spidev#.#
//
// Optional parameters for PWM, see [adaptors.NewPWMPinsAdaptor]
func NewPocketBeagleAdaptor(opts ...interface{}) *PocketBeagleAdaptor {

View File

@ -41,7 +41,7 @@ type Adaptor struct {
// Optional parameters:
//
// adaptors.WithGpiodAccess(): use character device gpiod driver instead of sysfs
// adaptors.WithSpiGpioAccess(sclk, nss, mosi, miso): use GPIO's instead of /dev/spidev#.#
// adaptors.WithSpiGpioAccess(sclk, ncs, sdo, sdi): use GPIO's instead of /dev/spidev#.#
//
// Optional parameters for PWM, see [adaptors.NewPWMPinsAdaptor]
func NewAdaptor(opts ...interface{}) *Adaptor {

View File

@ -339,7 +339,7 @@ void spi_init(littleWire* lwHandle);
void spi_sendMessage(littleWire* lwHandle, unsigned char * sendBuffer, unsigned char * inputBuffer, unsigned char length ,unsigned char mode);
/**
* Send one byte SPI message over MOSI pin. Slightly slower than the actual one.
* Send one byte SPI message over SDO pin. Slightly slower than the actual one.
* \n There isn't any chip select control involved. Useful for debug console app
*
* @param lwHandle littleWire device pointer
@ -376,7 +376,7 @@ void i2c_init(littleWire* lwHandle);
* Start the i2c communication
*
* @param lwHandle littleWire device pointer
* @param address 7 bit slave address.
* @param address 7 bit target address.
* @param direction ( \b READ or \b WRITE )
* @return 1 if received ACK
*/

View File

@ -49,7 +49,7 @@ var fixedPins = map[string]int{
// Optional parameters:
//
// adaptors.WithGpiodAccess(): use character device gpiod driver instead of sysfs
// adaptors.WithSpiGpioAccess(sclk, nss, mosi, miso): use GPIO's instead of /dev/spidev#.#
// adaptors.WithSpiGpioAccess(sclk, ncs, sdo, sdi): use GPIO's instead of /dev/spidev#.#
func NewAdaptor(opts ...func(adaptors.DigitalPinsOptioner)) *Adaptor {
sys := system.NewAccesser()
c := &Adaptor{

View File

@ -86,13 +86,13 @@ func (imu *IMUDriver) Start() error {
// Halt stops the IMUDriver
func (imu *IMUDriver) Halt() error { return nil }
// Name returns the IMUDriver's name
// Name returns the IMUDrivers name
func (imu *IMUDriver) Name() string { return imu.name }
// SetName sets the IMUDriver'ss name
// SetName sets the IMUDrivers name
func (imu *IMUDriver) SetName(n string) { imu.name = n }
// Connection returns the IMUDriver's Connection
// Connection returns the IMUDrivers Connection
func (imu *IMUDriver) Connection() gobot.Connection { return imu.connection }
// ReadAccelerometer calls the Curie's built-in accelerometer. The result will

View File

@ -33,7 +33,7 @@ type Adaptor struct {
// Optional parameters:
//
// adaptors.WithGpiodAccess(): use character device gpiod driver instead of sysfs
// adaptors.WithSpiGpioAccess(sclk, nss, mosi, miso): use GPIO's instead of /dev/spidev#.#
// adaptors.WithSpiGpioAccess(sclk, ncs, sdo, sdi): use GPIO's instead of /dev/spidev#.#
//
// Optional parameters for PWM, see [adaptors.NewPWMPinsAdaptor]
func NewAdaptor(opts ...interface{}) *Adaptor {

View File

@ -41,7 +41,7 @@ type Adaptor struct {
// Optional parameters:
//
// adaptors.WithGpiodAccess(): use character device gpiod driver instead of sysfs
// adaptors.WithSpiGpioAccess(sclk, nss, mosi, miso): use GPIO's instead of /dev/spidev#.#
// adaptors.WithSpiGpioAccess(sclk, ncs, sdo, sdi): use GPIO's instead of /dev/spidev#.#
//
// Optional parameters for PWM, see [adaptors.NewPWMPinsAdaptor]
func NewAdaptor(opts ...interface{}) *Adaptor {

View File

@ -451,7 +451,7 @@ const (
MAV_CMD_DO_PARACHUTE = 208 // Mission command to trigger a parachute | action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.) | Empty | Empty | Empty | Empty | Empty | Empty |
MAV_CMD_DO_INVERTED_FLIGHT = 210 // Change to/from inverted flight | inverted (0=normal, 1=inverted) | Empty | Empty | Empty | Empty | Empty | Empty |
MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220 // Mission command to control a camera or antenna mount, using a quaternion as reference. | q1 - quaternion param #1, w (1 in null-rotation) | q2 - quaternion param #2, x (0 in null-rotation) | q3 - quaternion param #3, y (0 in null-rotation) | q4 - quaternion param #4, z (0 in null-rotation) | Empty | Empty | Empty |
MAV_CMD_DO_GUIDED_MASTER = 221 // set id of master controller | System ID | Component ID | Empty | Empty | Empty | Empty | Empty |
MAV_CMD_DO_GUIDED_CONTROLLER = 221 // set id of the controller | System ID | Component ID | Empty | Empty | Empty | Empty | Empty |
MAV_CMD_DO_GUIDED_LIMITS = 222 // set limits for external control | timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout | absolute altitude min (in meters, WGS84) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit | absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit | horizontal move limit (in meters, WGS84) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit | Empty | Empty | Empty |
MAV_CMD_DO_LAST = 240 // NOP - This command is only used to mark the upper limit of the DO commands in the enumeration | Empty | Empty | Empty | Empty | Empty | Empty | Empty |
MAV_CMD_PREFLIGHT_CALIBRATION = 241 // Trigger calibration. This command will be only accepted if in pre-flight mode. | Gyro calibration: 0: no, 1: yes | Magnetometer calibration: 0: no, 1: yes | Ground pressure: 0: no, 1: yes | Radio calibration: 0: no, 1: yes | Accelerometer calibration: 0: no, 1: yes | Compass/Motor interference calibration: 0: no, 1: yes | Empty |
@ -879,7 +879,7 @@ func (m *SysStatus) Decode(buf []byte) {
//
// MAVLINK_MSG_ID_SYSTEM_TIME_CRC 137
type SystemTime struct {
TIME_UNIX_USEC uint64 // Timestamp of the master clock in microseconds since UNIX epoch.
TIME_UNIX_USEC uint64 // Timestamp of the primary reference clock in microseconds since UNIX epoch.
TIME_BOOT_MS uint32 // Timestamp of the component clock since boot time in milliseconds.
}

View File

@ -63,7 +63,7 @@ type Adaptor struct {
// Optional parameters:
//
// adaptors.WithGpiodAccess(): use character device gpiod driver instead of sysfs (still used by default)
// adaptors.WithSpiGpioAccess(sclk, nss, mosi, miso): use GPIO's instead of /dev/spidev#.#
// adaptors.WithSpiGpioAccess(sclk, ncs, sdo, sdi): use GPIO's instead of /dev/spidev#.#
// adaptors.WithGpiosActiveLow(pin's): invert the pin behavior
// adaptors.WithGpiosPullUp/Down(pin's): sets the internal pull resistor
// adaptors.WithGpiosOpenDrain/Source(pin's): sets the output behavior

View File

@ -8,8 +8,8 @@ var neoGpioPins = map[string]gpioPinDefinition{
"13": {sysfs: 2, cdev: cdevPin{chip: 0, line: 2}}, // UART2_RTS/GPIOA2
"15": {sysfs: 3, cdev: cdevPin{chip: 0, line: 3}}, // UART2_CTS/GPIOA3
"12": {sysfs: 6, cdev: cdevPin{chip: 0, line: 6}}, // GPIOA6
"19": {sysfs: 64, cdev: cdevPin{chip: 0, line: 64}}, // SPI0_MOSI/GPIOC0
"21": {sysfs: 65, cdev: cdevPin{chip: 0, line: 65}}, // SPI0_MISO/GPIOC1
"19": {sysfs: 64, cdev: cdevPin{chip: 0, line: 64}}, // SPI0_SDO/GPIOC0
"21": {sysfs: 65, cdev: cdevPin{chip: 0, line: 65}}, // SPI0_SDI/GPIOC1
"23": {sysfs: 66, cdev: cdevPin{chip: 0, line: 66}}, // SPI0_CLK/GPIOC2
"24": {sysfs: 67, cdev: cdevPin{chip: 0, line: 67}}, // SPI0_CS/GPIOC3
"8": {sysfs: 198, cdev: cdevPin{chip: 0, line: 198}}, // UART1_TX/GPIOG6

View File

@ -48,7 +48,7 @@ type Adaptor struct {
// Optional parameters:
//
// adaptors.WithGpiodAccess(): use character device gpiod driver instead of sysfs (still used by default)
// adaptors.WithSpiGpioAccess(sclk, nss, mosi, miso): use GPIO's instead of /dev/spidev#.#
// adaptors.WithSpiGpioAccess(sclk, ncs, sdo, sdi): use GPIO's instead of /dev/spidev#.#
// adaptors.WithGpiosActiveLow(pin's): invert the pin behavior
// adaptors.WithGpiosPullUp/Down(pin's): sets the internal pull resistor
// adaptors.WithGpiosOpenDrain/Source(pin's): sets the output behavior

View File

@ -42,7 +42,7 @@ type Adaptor struct {
// Optional parameters:
//
// adaptors.WithGpiodAccess(): use character device gpiod driver instead of the default sysfs (NOT work on RockPi4C+!)
// adaptors.WithSpiGpioAccess(sclk, nss, mosi, miso): use GPIO's instead of /dev/spidev#.#
// adaptors.WithSpiGpioAccess(sclk, ncs, sdo, sdi): use GPIO's instead of /dev/spidev#.#
// adaptors.WithGpiosActiveLow(pin's): invert the pin behavior
func NewAdaptor(opts ...func(adaptors.DigitalPinsOptioner)) *Adaptor {
sys := system.NewAccesser()

View File

@ -61,7 +61,7 @@ type Adaptor struct {
// Optional parameters:
//
// adaptors.WithGpiodAccess(): use character device gpiod driver instead of sysfs (still used by default)
// adaptors.WithSpiGpioAccess(sclk, nss, mosi, miso): use GPIO's instead of /dev/spidev#.#
// adaptors.WithSpiGpioAccess(sclk, ncs, sdo, sdi): use GPIO's instead of /dev/spidev#.#
// adaptors.WithGpiosActiveLow(pin's): invert the pin behavior
// adaptors.WithGpiosPullUp/Down(pin's): sets the internal pull resistor
//

View File

@ -55,7 +55,7 @@ type Adaptor struct {
// Optional parameters:
//
// adaptors.WithGpiodAccess(): use character device gpiod driver instead of sysfs
// adaptors.WithSpiGpioAccess(sclk, nss, mosi, miso): use GPIO's instead of /dev/spidev#.#
// adaptors.WithSpiGpioAccess(sclk, ncs, sdo, sdi): use GPIO's instead of /dev/spidev#.#
//
// Optional parameters for PWM, see [adaptors.NewPWMPinsAdaptor]
func NewAdaptor(opts ...interface{}) *Adaptor {

View File

@ -66,8 +66,8 @@ gpiochip0 - 54 lines:
...
line 7: "SPI_CE1_N" unused input active-high
line 8: "SPI_CE0_N" unused input active-high
line 9: "SPI_MISO" unused input active-high
line 10: "SPI_MOSI" unused input active-high
line 9: "SPI_SDI" unused input active-high
line 10: "SPI_SDO" unused input active-high
line 11: "SPI_SCLK" unused input active-high
...
line 14: "TXD0" unused input active-high

View File

@ -23,7 +23,7 @@ In general there are different ioctl features for I2C
> Some calls are branched by kernels [i2c-dev.c:i2cdev_ioctl()](https://elixir.bootlin.com/linux/latest/source/drivers/i2c/i2c-dev.c#L392)
> to the next listed calls.
Set the device address `ioctl(file, I2C_SLAVE, long addr)`. The call set the address directly to the character device.
Set the device address `ioctl(file, I2C_TARGET, long addr)`. The call set the address directly to the character device.
Query the supported functions `ioctl(file, I2C_FUNCS, unsigned long *funcs)`. The call is converted to in-kernel function
[i2c.h:i2c_get_functionality()](https://elixir.bootlin.com/linux/latest/source/include/linux/i2c.h#L902)

View File

@ -16,9 +16,9 @@ const (
const (
// From /usr/include/linux/i2c-dev.h:
// ioctl signals
I2C_SLAVE = 0x0703
I2C_FUNCS = 0x0705
I2C_SMBUS = 0x0720
I2C_TARGET = 0x0703
I2C_FUNCS = 0x0705
I2C_SMBUS = 0x0720
// Read/write markers
I2C_SMBUS_READ = 1
I2C_SMBUS_WRITE = 0
@ -371,7 +371,7 @@ func (d *i2cDevice) setAddress(address int) error {
return nil
}
if err := d.syscallIoctl(I2C_SLAVE, nil, address, "Setting address"); err != nil {
if err := d.syscallIoctl(I2C_TARGET, nil, address, "Setting address"); err != nil {
return err
}
d.lastAddress = address

View File

@ -34,7 +34,7 @@ func getSyscallFuncImpl(
I2C_FUNC_SMBUS_WRITE_WORD_DATA
}
// set address
if (trap == Syscall_SYS_IOCTL) && (a2 == I2C_SLAVE) {
if (trap == Syscall_SYS_IOCTL) && (a2 == I2C_TARGET) {
if errorMask&0x02 == 0x02 {
return 0, 0, 1
}

View File

@ -12,9 +12,9 @@ import (
type spiGpioConfig struct {
pinProvider gobot.DigitalPinnerProvider
sclkPinID string
nssPinID string
mosiPinID string
misoPinID string
ncsPinID string
sdoPinID string
sdiPinID string
}
// spiGpio is the implementation of the SPI interface using GPIO's.
@ -23,9 +23,9 @@ type spiGpio struct {
// time between clock edges (i.e. half the cycle time)
tclk time.Duration
sclkPin gobot.DigitalPinner
nssPin gobot.DigitalPinner
mosiPin gobot.DigitalPinner
misoPin gobot.DigitalPinner
ncsPin gobot.DigitalPinner
sdoPin gobot.DigitalPinner
sdiPin gobot.DigitalPinner
}
// newSpiGpio creates and returns a new SPI connection based on given GPIO's.
@ -60,7 +60,7 @@ func (s *spiGpio) TxRx(tx []byte, rx []byte) error {
}
}
if err := s.nssPin.Write(0); err != nil {
if err := s.ncsPin.Write(0); err != nil {
return err
}
@ -74,7 +74,7 @@ func (s *spiGpio) TxRx(tx []byte, rx []byte) error {
}
}
return s.nssPin.Write(1)
return s.ncsPin.Write(1)
}
// Close the SPI connection. Implements gobot.SpiSystemDevicer.
@ -85,18 +85,18 @@ func (s *spiGpio) Close() error {
err = multierror.Append(err, e)
}
}
if s.mosiPin != nil {
if e := s.mosiPin.Unexport(); e != nil {
if s.sdoPin != nil {
if e := s.sdoPin.Unexport(); e != nil {
err = multierror.Append(err, e)
}
}
if s.misoPin != nil {
if e := s.misoPin.Unexport(); e != nil {
if s.sdiPin != nil {
if e := s.sdiPin.Unexport(); e != nil {
err = multierror.Append(err, e)
}
}
if s.nssPin != nil {
if e := s.nssPin.Unexport(); e != nil {
if s.ncsPin != nil {
if e := s.ncsPin.Unexport(); e != nil {
err = multierror.Append(err, e)
}
}
@ -104,7 +104,7 @@ func (s *spiGpio) Close() error {
}
func (cfg *spiGpioConfig) String() string {
return fmt.Sprintf("sclk: %s, nss: %s, mosi: %s, miso: %s", cfg.sclkPinID, cfg.nssPinID, cfg.mosiPinID, cfg.misoPinID)
return fmt.Sprintf("sclk: %s, ncs: %s, sdo: %s, sdi: %s", cfg.sclkPinID, cfg.ncsPinID, cfg.sdoPinID, cfg.sdiPinID)
}
// transferByte simultaneously transmit and receive a byte
@ -116,7 +116,7 @@ func (s *spiGpio) transferByte(txByte uint8) (uint8, error) {
bitMask := uint8(0x80) // start at MSBit
for i := 0; i < 8; i++ {
if err := s.mosiPin.Write(int(txByte & bitMask)); err != nil {
if err := s.sdoPin.Write(int(txByte & bitMask)); err != nil {
return 0, err
}
@ -125,7 +125,7 @@ func (s *spiGpio) transferByte(txByte uint8) (uint8, error) {
return 0, err
}
v, err := s.misoPin.Read()
v, err := s.sdiPin.Read()
if err != nil {
return 0, err
}
@ -146,12 +146,12 @@ func (s *spiGpio) transferByte(txByte uint8) (uint8, error) {
func (s *spiGpio) initializeGpios() error {
var err error
// nss is an output, negated (currently not implemented at pin level)
s.nssPin, err = s.cfg.pinProvider.DigitalPin(s.cfg.nssPinID)
// ncs is an output, negated (currently not implemented at pin level)
s.ncsPin, err = s.cfg.pinProvider.DigitalPin(s.cfg.ncsPinID)
if err != nil {
return err
}
if err := s.nssPin.ApplyOptions(WithPinDirectionOutput(1)); err != nil {
if err := s.ncsPin.ApplyOptions(WithPinDirectionOutput(1)); err != nil {
return err
}
// sclk is an output, CPOL = 0
@ -162,15 +162,15 @@ func (s *spiGpio) initializeGpios() error {
if err := s.sclkPin.ApplyOptions(WithPinDirectionOutput(0)); err != nil {
return err
}
// miso is an input
s.misoPin, err = s.cfg.pinProvider.DigitalPin(s.cfg.misoPinID)
// sdi is an input
s.sdiPin, err = s.cfg.pinProvider.DigitalPin(s.cfg.sdiPinID)
if err != nil {
return err
}
// mosi is an output
s.mosiPin, err = s.cfg.pinProvider.DigitalPin(s.cfg.mosiPinID)
// sdo is an output
s.sdoPin, err = s.cfg.pinProvider.DigitalPin(s.cfg.sdoPinID)
if err != nil {
return err
}
return s.mosiPin.ApplyOptions(WithPinDirectionOutput(0))
return s.sdoPin.ApplyOptions(WithPinDirectionOutput(0))
}

View File

@ -39,7 +39,7 @@ func (sys *nativeSyscall) syscall(
address uint16,
) (r1, r2 uintptr, err SyscallErrno) {
var errNo unix.Errno
if signal == I2C_SLAVE {
if signal == I2C_TARGET {
// this is the setup for the address, it just needs to be converted to an uintptr,
// the given payload is not used in this case, see the comment on the function
r1, r2, errNo = unix.Syscall(trap, f.Fd(), signal, uintptr(address))

View File

@ -30,7 +30,7 @@ func (sys *mockSyscall) syscall(
sys.lastFile = f // a character device file (e.g. file to path "/dev/i2c-1")
sys.lastSignal = signal // points to used function type (e.g. I2C_SMBUS, I2C_RDWR)
if signal == I2C_SLAVE {
if signal == I2C_TARGET {
// this is the setup for the address, it needs to be converted to an uintptr,
// the given payload is not used in this case, see the comment on the function used for production
sys.devAddress = uintptr(address)

View File

@ -10,7 +10,7 @@ import (
// caller/user when creating the system access, e.g. by "NewAccesser()".
type Optioner interface {
setDigitalPinToGpiodAccess()
setSpiToGpioAccess(p gobot.DigitalPinnerProvider, sclkPin, nssPin, mosiPin, misoPin string)
setSpiToGpioAccess(p gobot.DigitalPinnerProvider, sclkPin, ncsPin, sdoPin, sdiPin string)
}
// WithDigitalPinGpiodAccess can be used to change the default sysfs implementation for digital pins to the character
@ -22,9 +22,9 @@ func WithDigitalPinGpiodAccess() func(Optioner) {
}
// WithSpiGpioAccess can be used to switch the default SPI implementation to GPIO usage.
func WithSpiGpioAccess(p gobot.DigitalPinnerProvider, sclkPin, nssPin, mosiPin, misoPin string) func(Optioner) {
func WithSpiGpioAccess(p gobot.DigitalPinnerProvider, sclkPin, ncsPin, sdoPin, sdiPin string) func(Optioner) {
return func(s Optioner) {
s.setSpiToGpioAccess(p, sclkPin, nssPin, mosiPin, misoPin)
s.setSpiToGpioAccess(p, sclkPin, ncsPin, sdoPin, sdiPin)
}
}
@ -42,13 +42,13 @@ func (a *Accesser) setDigitalPinToGpiodAccess() {
}
}
func (a *Accesser) setSpiToGpioAccess(p gobot.DigitalPinnerProvider, sclkPin, nssPin, mosiPin, misoPin string) {
func (a *Accesser) setSpiToGpioAccess(p gobot.DigitalPinnerProvider, sclkPin, ncsPin, sdoPin, sdiPin string) {
cfg := spiGpioConfig{
pinProvider: p,
sclkPinID: sclkPin,
nssPinID: nssPin,
mosiPinID: mosiPin,
misoPinID: misoPin,
ncsPinID: ncsPin,
sdoPinID: sdoPin,
sdiPinID: sdiPin,
}
gsa := &gpioSpiAccess{cfg: cfg}
if gsa.isSupported() {