Skip to content

Commit bfba1ab

Browse files
authored
i2c/spi: remove offensive terminology (hybridgroup#1071)
1 parent c159228 commit bfba1ab

28 files changed

+74
-74
lines changed

drivers/i2c/i2c_connection_test.go

+1-1
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@ func getSyscallFuncImpl(
3737
system.I2C_FUNC_SMBUS_WRITE_WORD_DATA
3838
}
3939
// set address
40-
if (trap == system.Syscall_SYS_IOCTL) && (a2 == system.I2C_SLAVE) {
40+
if (trap == system.Syscall_SYS_IOCTL) && (a2 == system.I2C_TARGET) {
4141
if errorMask&0x02 == 0x02 {
4242
return 0, 0, 1
4343
}

examples/tinkerboard_mfcrc522gpio.go

+5-5
Original file line numberDiff line numberDiff line change
@@ -19,17 +19,17 @@ import (
1919
// Wiring
2020
// PWR Tinkerboard: 1 (+3.3V, VCC), 2(+5V), 6, 9, 14, 20 (GND)
2121
// GPIO-SPI Tinkerboard (same as SPI2): 23 (CLK), 19 (TXD), 21 (RXD), 24 (CSN0)
22-
// MFRC522 plate: VCC, GND, SCK (CLK), MOSI (->TXD), MISO (->RXD), NSS/SDA (CSN0/CSN1?)
22+
// MFRC522 plate: VCC, GND, SCK (CLK), SDO (->TXD), SDI (->RXD), NCS/SDA (CSN0/CSN1?)
2323
const (
2424
sclk = "23"
25-
nss = "24"
26-
mosi = "19"
27-
miso = "21"
25+
ncs = "24"
26+
sdo = "19"
27+
sdi = "21"
2828
speedHz = 5000 // more than 15kHz is not possible with GPIO's, so we choose 5kHz
2929
)
3030

3131
func main() {
32-
a := tinkerboard.NewAdaptor(adaptors.WithSpiGpioAccess(sclk, nss, mosi, miso))
32+
a := tinkerboard.NewAdaptor(adaptors.WithSpiGpioAccess(sclk, ncs, sdo, sdi))
3333
d := spi.NewMFRC522Driver(a, spi.WithSpeed(speedHz))
3434

3535
wasCardDetected := false

examples/tinkerboard_mfcrc522spi.go

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

platforms/adaptors/digitalpinsadaptor.go

+2-2
Original file line numberDiff line numberDiff line change
@@ -63,9 +63,9 @@ func WithGpiodAccess() func(DigitalPinsOptioner) {
6363
}
6464

6565
// WithSpiGpioAccess can be used to switch the default SPI implementation to GPIO usage.
66-
func WithSpiGpioAccess(sclkPin, nssPin, mosiPin, misoPin string) func(DigitalPinsOptioner) {
66+
func WithSpiGpioAccess(sclkPin, ncsPin, sdoPin, sdiPin string) func(DigitalPinsOptioner) {
6767
return func(o DigitalPinsOptioner) {
68-
o.setDigitalPinsForSystemSpi(sclkPin, nssPin, mosiPin, misoPin)
68+
o.setDigitalPinsForSystemSpi(sclkPin, ncsPin, sdoPin, sdiPin)
6969
}
7070
}
7171

platforms/adaptors/digitalpinsadaptoroptions.go

+3-3
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@ import (
1313
type DigitalPinsOptioner interface {
1414
setDigitalPinInitializer(initializer digitalPinInitializer)
1515
setDigitalPinsForSystemGpiod()
16-
setDigitalPinsForSystemSpi(sclkPin, nssPin, mosiPin, misoPin string)
16+
setDigitalPinsForSystemSpi(sclkPin, ncsPin, sdoPin, sdiPin string)
1717
prepareDigitalPinsActiveLow(pin string, otherPins ...string)
1818
prepareDigitalPinsPullDown(pin string, otherPins ...string)
1919
prepareDigitalPinsPullUp(pin string, otherPins ...string)
@@ -37,8 +37,8 @@ func (a *DigitalPinsAdaptor) setDigitalPinsForSystemGpiod() {
3737
system.WithDigitalPinGpiodAccess()(a.sys)
3838
}
3939

40-
func (a *DigitalPinsAdaptor) setDigitalPinsForSystemSpi(sclkPin, nssPin, mosiPin, misoPin string) {
41-
system.WithSpiGpioAccess(a, sclkPin, nssPin, mosiPin, misoPin)(a.sys)
40+
func (a *DigitalPinsAdaptor) setDigitalPinsForSystemSpi(sclkPin, ncsPin, sdoPin, sdiPin string) {
41+
system.WithSpiGpioAccess(a, sclkPin, ncsPin, sdoPin, sdiPin)(a.sys)
4242
}
4343

4444
func (a *DigitalPinsAdaptor) prepareDigitalPinsActiveLow(id string, otherIDs ...string) {

platforms/beaglebone/beaglebone_adaptor.go

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

platforms/beaglebone/pocketbeagle_adaptor.go

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

platforms/chip/chip_adaptor.go

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

platforms/digispark/littleWire.h

+2-2
Original file line numberDiff line numberDiff line change
@@ -339,7 +339,7 @@ void spi_init(littleWire* lwHandle);
339339
void spi_sendMessage(littleWire* lwHandle, unsigned char * sendBuffer, unsigned char * inputBuffer, unsigned char length ,unsigned char mode);
340340

341341
/**
342-
* Send one byte SPI message over MOSI pin. Slightly slower than the actual one.
342+
* Send one byte SPI message over SDO pin. Slightly slower than the actual one.
343343
* \n There isn't any chip select control involved. Useful for debug console app
344344
*
345345
* @param lwHandle littleWire device pointer
@@ -376,7 +376,7 @@ void i2c_init(littleWire* lwHandle);
376376
* Start the i2c communication
377377
*
378378
* @param lwHandle littleWire device pointer
379-
* @param address 7 bit slave address.
379+
* @param address 7 bit target address.
380380
* @param direction ( \b READ or \b WRITE )
381381
* @return 1 if received ACK
382382
*/

platforms/dragonboard/dragonboard_adaptor.go

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

platforms/intel-iot/curie/imu_driver.go

+3-3
Original file line numberDiff line numberDiff line change
@@ -86,13 +86,13 @@ func (imu *IMUDriver) Start() error {
8686
// Halt stops the IMUDriver
8787
func (imu *IMUDriver) Halt() error { return nil }
8888

89-
// Name returns the IMUDriver's name
89+
// Name returns the IMUDrivers name
9090
func (imu *IMUDriver) Name() string { return imu.name }
9191

92-
// SetName sets the IMUDriver'ss name
92+
// SetName sets the IMUDrivers name
9393
func (imu *IMUDriver) SetName(n string) { imu.name = n }
9494

95-
// Connection returns the IMUDriver's Connection
95+
// Connection returns the IMUDrivers Connection
9696
func (imu *IMUDriver) Connection() gobot.Connection { return imu.connection }
9797

9898
// ReadAccelerometer calls the Curie's built-in accelerometer. The result will

platforms/intel-iot/joule/joule_adaptor.go

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

platforms/jetson/jetson_adaptor.go

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

platforms/mavlink/common/common.go

+2-2
Original file line numberDiff line numberDiff line change
@@ -451,7 +451,7 @@ const (
451451
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 |
452452
MAV_CMD_DO_INVERTED_FLIGHT = 210 // Change to/from inverted flight | inverted (0=normal, 1=inverted) | Empty | Empty | Empty | Empty | Empty | Empty |
453453
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 |
454-
MAV_CMD_DO_GUIDED_MASTER = 221 // set id of master controller | System ID | Component ID | Empty | Empty | Empty | Empty | Empty |
454+
MAV_CMD_DO_GUIDED_CONTROLLER = 221 // set id of the controller | System ID | Component ID | Empty | Empty | Empty | Empty | Empty |
455455
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 |
456456
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 |
457457
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) {
879879
//
880880
// MAVLINK_MSG_ID_SYSTEM_TIME_CRC 137
881881
type SystemTime struct {
882-
TIME_UNIX_USEC uint64 // Timestamp of the master clock in microseconds since UNIX epoch.
882+
TIME_UNIX_USEC uint64 // Timestamp of the primary reference clock in microseconds since UNIX epoch.
883883
TIME_BOOT_MS uint32 // Timestamp of the component clock since boot time in milliseconds.
884884
}
885885

platforms/nanopi/nanopi_adaptor.go

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

platforms/nanopi/nanopineo_pin_map.go

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

platforms/raspi/raspi_adaptor.go

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

platforms/rockpi/rockpi_adaptor.go

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

platforms/tinkerboard/adaptor.go

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

platforms/upboard/up2/adaptor.go

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

system/GPIO.md

+2-2
Original file line numberDiff line numberDiff line change
@@ -66,8 +66,8 @@ gpiochip0 - 54 lines:
6666
...
6767
line 7: "SPI_CE1_N" unused input active-high
6868
line 8: "SPI_CE0_N" unused input active-high
69-
line 9: "SPI_MISO" unused input active-high
70-
line 10: "SPI_MOSI" unused input active-high
69+
line 9: "SPI_SDI" unused input active-high
70+
line 10: "SPI_SDO" unused input active-high
7171
line 11: "SPI_SCLK" unused input active-high
7272
...
7373
line 14: "TXD0" unused input active-high

system/I2C.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@ In general there are different ioctl features for I2C
2323
> Some calls are branched by kernels [i2c-dev.c:i2cdev_ioctl()](https://elixir.bootlin.com/linux/latest/source/drivers/i2c/i2c-dev.c#L392)
2424
> to the next listed calls.
2525
26-
Set the device address `ioctl(file, I2C_SLAVE, long addr)`. The call set the address directly to the character device.
26+
Set the device address `ioctl(file, I2C_TARGET, long addr)`. The call set the address directly to the character device.
2727

2828
Query the supported functions `ioctl(file, I2C_FUNCS, unsigned long *funcs)`. The call is converted to in-kernel function
2929
[i2c.h:i2c_get_functionality()](https://elixir.bootlin.com/linux/latest/source/include/linux/i2c.h#L902)

system/i2c_device.go

+4-4
Original file line numberDiff line numberDiff line change
@@ -16,9 +16,9 @@ const (
1616
const (
1717
// From /usr/include/linux/i2c-dev.h:
1818
// ioctl signals
19-
I2C_SLAVE = 0x0703
20-
I2C_FUNCS = 0x0705
21-
I2C_SMBUS = 0x0720
19+
I2C_TARGET = 0x0703
20+
I2C_FUNCS = 0x0705
21+
I2C_SMBUS = 0x0720
2222
// Read/write markers
2323
I2C_SMBUS_READ = 1
2424
I2C_SMBUS_WRITE = 0
@@ -371,7 +371,7 @@ func (d *i2cDevice) setAddress(address int) error {
371371
return nil
372372
}
373373

374-
if err := d.syscallIoctl(I2C_SLAVE, nil, address, "Setting address"); err != nil {
374+
if err := d.syscallIoctl(I2C_TARGET, nil, address, "Setting address"); err != nil {
375375
return err
376376
}
377377
d.lastAddress = address

system/i2c_device_test.go

+1-1
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ func getSyscallFuncImpl(
3434
I2C_FUNC_SMBUS_WRITE_WORD_DATA
3535
}
3636
// set address
37-
if (trap == Syscall_SYS_IOCTL) && (a2 == I2C_SLAVE) {
37+
if (trap == Syscall_SYS_IOCTL) && (a2 == I2C_TARGET) {
3838
if errorMask&0x02 == 0x02 {
3939
return 0, 0, 1
4040
}

0 commit comments

Comments
 (0)