SPI Device with cgo

master
Friedl Ulrich 10 years ago
parent 1882b30340
commit 8c72397bb4

@ -1,252 +0,0 @@
package generic
import (
"fmt"
"os"
"sync"
"syscall"
"unsafe"
"github.com/golang/glog"
"github.com/kidoman/embd"
)
const (
spiIOCWrMode = 0x40016B01
spiIOCWrBitsPerWord = 0x40016B03
spiIOCWrMaxSpeedHz = 0x40046B04
spiIOCRdMode = 0x80016B01
spiIOCRdBitsPerWord = 0x80016B03
spiIOCRdMaxSpeedHz = 0x80046B04
spiIOCMessage0 = 1073769216 //0x40006B00
spiIOCIncrementor = 2097152 //0x200000
defaultDelayms = 0
defaultSPIBPW = 8
defaultSPISpeed = 1000000
)
type spiIOCTransfer struct {
txBuf uint64
rxBuf uint64
length uint32
speedHz uint32
delayus uint16
bitsPerWord uint8
}
type spiBus struct {
file *os.File
spiDevMinor byte
channel byte
mode byte
speed int
bpw int
delayms int
mu sync.Mutex
spiTransferData spiIOCTransfer
initialized bool
initializer func() error
}
func spiIOCMessageN(n uint32) uint32 {
return (spiIOCMessage0 + (n * spiIOCIncrementor))
}
func NewSPIBus(spiDevMinor, mode, channel byte, speed, bpw, delay int, i func() error) embd.SPIBus {
return &spiBus{
spiDevMinor: spiDevMinor,
mode: mode,
channel: channel,
speed: speed,
bpw: bpw,
delayms: delay,
initializer: i,
}
}
func (b *spiBus) init() error {
if b.initialized {
return nil
}
if b.initializer != nil {
if err := b.initializer(); err != nil {
return err
}
}
var err error
if b.file, err = os.OpenFile(fmt.Sprintf("/dev/spidev%v.%v", b.spiDevMinor, b.channel), os.O_RDWR, os.ModeExclusive); err != nil {
return err
}
glog.V(3).Infof("spi: sucessfully opened file /dev/spidev%v.%v", b.spiDevMinor, b.channel)
if err = b.setMode(); err != nil {
return err
}
b.spiTransferData = spiIOCTransfer{}
if err = b.setSpeed(); err != nil {
return err
}
if err = b.setBPW(); err != nil {
return err
}
b.setDelay()
glog.V(2).Infof("spi: bus %v initialized", b.channel)
glog.V(3).Infof("spi: bus %v initialized with spiIOCTransfer as %v", b.channel, b.spiTransferData)
b.initialized = true
return nil
}
func (b *spiBus) setMode() error {
var mode = uint8(b.mode)
glog.V(3).Infof("spi: setting spi mode to %v", mode)
_, _, errno := syscall.Syscall(syscall.SYS_IOCTL, b.file.Fd(), spiIOCWrMode, uintptr(unsafe.Pointer(&mode)))
if errno != 0 {
err := syscall.Errno(errno)
glog.V(3).Infof("spi: failed to set mode due to %v", err.Error())
return err
}
glog.V(3).Infof("spi: mode set to %v", mode)
return nil
}
func (b *spiBus) setSpeed() error {
var speed uint32 = defaultSPISpeed
if b.speed > 0 {
speed = uint32(b.speed)
}
glog.V(3).Infof("spi: setting spi speedMax to %v", speed)
_, _, errno := syscall.Syscall(syscall.SYS_IOCTL, b.file.Fd(), spiIOCWrMaxSpeedHz, uintptr(unsafe.Pointer(&speed)))
if errno != 0 {
err := syscall.Errno(errno)
glog.V(3).Infof("spi: failed to set speedMax due to %v", err.Error())
return err
}
glog.V(3).Infof("spi: speedMax set to %v", speed)
b.spiTransferData.speedHz = speed
return nil
}
func (b *spiBus) setBPW() error {
var bpw uint8 = defaultSPIBPW
if b.bpw > 0 {
bpw = uint8(b.bpw)
}
glog.V(3).Infof("spi: setting spi bpw to %v", bpw)
_, _, errno := syscall.Syscall(syscall.SYS_IOCTL, b.file.Fd(), spiIOCWrBitsPerWord, uintptr(unsafe.Pointer(&bpw)))
if errno != 0 {
err := syscall.Errno(errno)
glog.V(3).Infof("spi: failed to set bpw due to %v", err.Error())
return err
}
glog.V(3).Infof("spi: bpw set to %v", bpw)
b.spiTransferData.bitsPerWord = uint8(bpw)
return nil
}
func (b *spiBus) setDelay() {
var delay uint16 = defaultDelayms
if b.delayms > 0 {
delay = uint16(b.delayms)
}
glog.V(3).Infof("spi: delayms set to %v", delay)
b.spiTransferData.delayus = delay
}
func (b *spiBus) TransferAndRecieveData(dataBuffer []uint8) error {
if err := b.init(); err != nil {
return err
}
len := len(dataBuffer)
dataCarrier := b.spiTransferData
dataCarrier.length = uint32(len)
dataCarrier.txBuf = uint64(uintptr(unsafe.Pointer(&dataBuffer[0])))
dataCarrier.rxBuf = uint64(uintptr(unsafe.Pointer(&dataBuffer[0])))
glog.V(3).Infof("spi: sending dataBuffer %v with carrier %v", dataBuffer, dataCarrier)
_, _, errno := syscall.Syscall(syscall.SYS_IOCTL, b.file.Fd(), uintptr(spiIOCMessageN(1)), uintptr(unsafe.Pointer(&dataCarrier)))
if errno != 0 {
err := syscall.Errno(errno)
glog.V(3).Infof("spi: failed to read due to %v", err.Error())
return err
}
glog.V(3).Infof("spi: read into dataBuffer %v", dataBuffer)
return nil
}
func (b *spiBus) ReceiveData(len int) ([]uint8, error) {
if err := b.init(); err != nil {
return nil, err
}
data := make([]uint8, len)
if err := b.TransferAndRecieveData(data); err != nil {
return nil, err
}
return data, nil
}
func (b *spiBus) TransferAndReceiveByte(data byte) (byte, error) {
if err := b.init(); err != nil {
return 0, err
}
d := [1]uint8{uint8(data)}
if err := b.TransferAndRecieveData(d[:]); err != nil {
return 0, err
}
return d[0], nil
}
func (b *spiBus) ReceiveByte() (byte, error) {
if err := b.init(); err != nil {
return 0, err
}
var d [1]uint8
if err := b.TransferAndRecieveData(d[:]); err != nil {
return 0, err
}
return byte(d[0]), nil
}
func (b *spiBus) Write(data []byte) (n int, err error) {
if err := b.init(); err != nil {
return 0, err
}
return b.file.Write(data)
}
func (b *spiBus) Close() error {
b.mu.Lock()
defer b.mu.Unlock()
if !b.initialized {
return nil
}
return b.file.Close()
}

@ -5,33 +5,28 @@ import (
"github.com/kidoman/embd"
_ "github.com/fulr/rfm69/rpi"
_ "github.com/kidoman/embd/host/rpi"
)
func TestRfm69(t *testing.T) {
t.Log("Test")
if err := embd.InitSPI(); err != nil {
t.Error(err)
}
defer embd.CloseSPI()
if err := embd.InitGPIO(); err != nil {
panic(err)
}
defer embd.CloseGPIO()
gpio, err := embd.NewDigitalPin(10)
gpio, err := embd.NewDigitalPin(25)
if err != nil {
panic(err)
}
defer gpio.Close()
//if err := gpio.SetDirection(embd.In); err != nil {
// panic(err)
//}
//gpio.ActiveLow(false)
if err := gpio.SetDirection(embd.In); err != nil {
panic(err)
}
gpio.ActiveLow(false)
spiBus := embd.NewSPIBus(embd.SPIMode0, 0, 4000000, 8, 0)
spiBus := NewSPIDevice()
defer spiBus.Close()
rfm, err := NewDevice(spiBus, gpio, 1, 10, true)

@ -9,7 +9,7 @@ import (
// Device RFM69 Device
type Device struct {
SpiDevice embd.SPIBus
SpiDevice *SPIDevice
gpio embd.DigitalPin
mode byte
address byte
@ -25,7 +25,7 @@ const (
)
// NewDevice creates a new device
func NewDevice(spi embd.SPIBus, gpio embd.DigitalPin, nodeID, networkID byte, isRfm69HW bool) (*Device, error) {
func NewDevice(spi *SPIDevice, gpio embd.DigitalPin, nodeID, networkID byte, isRfm69HW bool) (*Device, error) {
ret := &Device{
SpiDevice: spi,
gpio: gpio,
@ -42,11 +42,11 @@ func NewDevice(spi embd.SPIBus, gpio embd.DigitalPin, nodeID, networkID byte, is
}
func (r *Device) writeReg(addr, data byte) error {
tx := make([]uint8, 2)
tx := make([]byte, 2)
tx[0] = addr | 0x80
tx[1] = data
log.Printf("write %x: %x", addr, data)
err := r.SpiDevice.TransferAndRecieveData(tx)
rx, err := r.SpiDevice.Xfer(tx)
if err != nil {
log.Println(err)
}
@ -58,7 +58,7 @@ func (r *Device) readReg(addr byte) (byte, error) {
tx[0] = addr & 0x7f
tx[1] = 0
log.Printf("read %x", addr)
err := r.SpiDevice.TransferAndRecieveData(tx)
err := r.SpiDevice.Xfer(tx)
if err != nil {
log.Println(err)
}
@ -178,7 +178,7 @@ func (r *Device) encrypt(key []byte) error {
tx := make([]byte, 17)
tx[0] = REG_AESKEY1 | 0x80
copy(tx[1:], key)
if err := r.SpiDevice.TransferAndRecieveData(tx); err != nil {
if rx, err := r.SpiDevice.Xfer(tx); err != nil {
return err
}
}

@ -0,0 +1,108 @@
package rfm69
/*
#include <linux/spi/spidev.h>
uint8_t mode=0;
uint8_t bits=8;
uint32_t speed=SPI_SPEED;
int spi_open(const char *device) {
int fd = open(device, O_RDWR);
int ret;
if (fd < 0) {
printf("can't open device");
return -1;
}
ret = ioctl(fd, SPI_IOC_WR_MODE, &mode);
if (ret == -1) {
printf("can't set spi mode");
return -1;
}
ret = ioctl(fd, SPI_IOC_RD_MODE, &mode);
if (ret == -1) {
printf("can't get spi mode");
return -1;
}
ret = ioctl(fd, SPI_IOC_WR_BITS_PER_WORD, &bits);
if (ret == -1) {
printf("can't set bits per word");
return -1;
}
ret = ioctl(fd, SPI_IOC_RD_BITS_PER_WORD, &bits);
if (ret == -1) {
printf("can't get bits per word");
return -1;
}
ret = ioctl(fd, SPI_IOC_WR_MAX_SPEED_HZ, &speed);
if (ret == -1) {
printf("can't set max speed hz");
return -1;
}
ret = ioctl(fd, SPI_IOC_RD_MAX_SPEED_HZ, &speed);
if (ret == -1) {
printf("can't get max speed hz");
return -1;
}
return fd;
}
int spi_xfer(int fd, char* tx, char* rx, int length) {
struct spi_ioc_transfer tr = {
.tx_buf = (unsigned long)tx,
.rx_buf = (unsigned long)rx,
.len = length,
.delay_usecs = delay,
.speed_hz = speed,
.bits_per_word = bits,
};
int ret = ioctl(fd, SPI_IOC_MESSAGE(1), &tr);
if (ret < 1)
return -1;
return 0;
}
*/
import "C"
import "unsafe"
// SPIDevice device
type SPIDevice struct {
fd int
}
// NewSPIDevice creates a new device
func NewSPIDevice() (*SPIDevice, error) {
name := C.CString("/dev/spidev0.0")
i := C.spi_open(name)
C.free(name)
if i < 0 {
return nil, error("")
}
return &SPIDevice{i}, nil
}
// Xfer cross transfer
func (d *SPIDevice) Xfer(tx []byte) ([]byte, error) {
length := len(tx)
rx := make([]byte, length)
ret := C.spi_xfer(d.fd, unsafe.Pointer(&tx[0]), unsafe.Pointer(&rx[0]), length)
if ret < 0 {
return nil, error("could not xfer")
}
return rx, nil
}
// Close closes the fd
func (d *SPIDevice) Close() {
C.close(d.fd)
}

@ -1,102 +0,0 @@
/*
Package rpi provides Raspberry Pi (including A+/B+) support.
The following features are supported on Linux kernel 3.8+
GPIO (digital (rw))
I²C
LED
*/
package rpi
import (
"github.com/kidoman/embd"
"github.com/kidoman/rfm69/generic"
)
var spiDeviceMinor = byte(0)
var rev1Pins = embd.PinMap{
&embd.PinDesc{ID: "P1_3", Aliases: []string{"0", "GPIO_0", "SDA", "I2C0_SDA"}, Caps: embd.CapDigital | embd.CapI2C, DigitalLogical: 0},
&embd.PinDesc{ID: "P1_5", Aliases: []string{"1", "GPIO_1", "SCL", "I2C0_SCL"}, Caps: embd.CapDigital | embd.CapI2C, DigitalLogical: 1},
&embd.PinDesc{ID: "P1_7", Aliases: []string{"4", "GPIO_4", "GPCLK0"}, Caps: embd.CapDigital, DigitalLogical: 4},
&embd.PinDesc{ID: "P1_8", Aliases: []string{"14", "GPIO_14", "TXD", "UART0_TXD"}, Caps: embd.CapDigital | embd.CapUART, DigitalLogical: 14},
&embd.PinDesc{ID: "P1_10", Aliases: []string{"15", "GPIO_15", "RXD", "UART0_RXD"}, Caps: embd.CapDigital | embd.CapUART, DigitalLogical: 15},
&embd.PinDesc{ID: "P1_11", Aliases: []string{"17", "GPIO_17"}, Caps: embd.CapDigital, DigitalLogical: 17},
&embd.PinDesc{ID: "P1_12", Aliases: []string{"18", "GPIO_18", "PCM_CLK"}, Caps: embd.CapDigital, DigitalLogical: 18},
&embd.PinDesc{ID: "P1_13", Aliases: []string{"21", "GPIO_21"}, Caps: embd.CapDigital, DigitalLogical: 21},
&embd.PinDesc{ID: "P1_15", Aliases: []string{"22", "GPIO_22"}, Caps: embd.CapDigital, DigitalLogical: 22},
&embd.PinDesc{ID: "P1_16", Aliases: []string{"23", "GPIO_23"}, Caps: embd.CapDigital, DigitalLogical: 23},
&embd.PinDesc{ID: "P1_18", Aliases: []string{"24", "GPIO_24"}, Caps: embd.CapDigital, DigitalLogical: 24},
&embd.PinDesc{ID: "P1_19", Aliases: []string{"10", "GPIO_10", "MOSI", "SPI0_MOSI"}, Caps: embd.CapDigital | embd.CapSPI, DigitalLogical: 10},
&embd.PinDesc{ID: "P1_21", Aliases: []string{"9", "GPIO_9", "MISO", "SPI0_MISO"}, Caps: embd.CapDigital | embd.CapSPI, DigitalLogical: 9},
&embd.PinDesc{ID: "P1_22", Aliases: []string{"25", "GPIO_25"}, Caps: embd.CapDigital, DigitalLogical: 25},
&embd.PinDesc{ID: "P1_23", Aliases: []string{"11", "GPIO_11", "SCLK", "SPI0_SCLK"}, Caps: embd.CapDigital | embd.CapSPI, DigitalLogical: 11},
&embd.PinDesc{ID: "P1_24", Aliases: []string{"8", "GPIO_8", "CE0", "SPI0_CE0_N"}, Caps: embd.CapDigital | embd.CapSPI, DigitalLogical: 8},
&embd.PinDesc{ID: "P1_26", Aliases: []string{"7", "GPIO_7", "CE1", "SPI0_CE1_N"}, Caps: embd.CapDigital | embd.CapSPI, DigitalLogical: 7},
}
var rev2Pins = embd.PinMap{
&embd.PinDesc{ID: "P1_3", Aliases: []string{"2", "GPIO_2", "SDA", "I2C1_SDA"}, Caps: embd.CapDigital | embd.CapI2C, DigitalLogical: 2},
&embd.PinDesc{ID: "P1_5", Aliases: []string{"3", "GPIO_3", "SCL", "I2C1_SCL"}, Caps: embd.CapDigital | embd.CapI2C, DigitalLogical: 3},
&embd.PinDesc{ID: "P1_7", Aliases: []string{"4", "GPIO_4", "GPCLK0"}, Caps: embd.CapDigital, DigitalLogical: 4},
&embd.PinDesc{ID: "P1_8", Aliases: []string{"14", "GPIO_14", "TXD", "UART0_TXD"}, Caps: embd.CapDigital | embd.CapUART, DigitalLogical: 14},
&embd.PinDesc{ID: "P1_10", Aliases: []string{"15", "GPIO_15", "RXD", "UART0_RXD"}, Caps: embd.CapDigital | embd.CapUART, DigitalLogical: 15},
&embd.PinDesc{ID: "P1_11", Aliases: []string{"17", "GPIO_17"}, Caps: embd.CapDigital, DigitalLogical: 17},
&embd.PinDesc{ID: "P1_12", Aliases: []string{"18", "GPIO_18", "PCM_CLK"}, Caps: embd.CapDigital, DigitalLogical: 18},
&embd.PinDesc{ID: "P1_13", Aliases: []string{"27", "GPIO_27"}, Caps: embd.CapDigital, DigitalLogical: 27},
&embd.PinDesc{ID: "P1_15", Aliases: []string{"22", "GPIO_22"}, Caps: embd.CapDigital, DigitalLogical: 22},
&embd.PinDesc{ID: "P1_16", Aliases: []string{"23", "GPIO_23"}, Caps: embd.CapDigital, DigitalLogical: 23},
&embd.PinDesc{ID: "P1_18", Aliases: []string{"24", "GPIO_24"}, Caps: embd.CapDigital, DigitalLogical: 24},
&embd.PinDesc{ID: "P1_19", Aliases: []string{"10", "GPIO_10", "MOSI", "SPI0_MOSI"}, Caps: embd.CapDigital | embd.CapSPI, DigitalLogical: 10},
&embd.PinDesc{ID: "P1_21", Aliases: []string{"9", "GPIO_9", "MISO", "SPI0_MISO"}, Caps: embd.CapDigital | embd.CapSPI, DigitalLogical: 9},
&embd.PinDesc{ID: "P1_22", Aliases: []string{"25", "GPIO_25"}, Caps: embd.CapDigital, DigitalLogical: 25},
&embd.PinDesc{ID: "P1_23", Aliases: []string{"11", "GPIO_11", "SCLK", "SPI0_SCLK"}, Caps: embd.CapDigital | embd.CapSPI, DigitalLogical: 11},
&embd.PinDesc{ID: "P1_24", Aliases: []string{"8", "GPIO_8", "CE0", "SPI0_CE0_N"}, Caps: embd.CapDigital | embd.CapSPI, DigitalLogical: 8},
&embd.PinDesc{ID: "P1_26", Aliases: []string{"7", "GPIO_7", "CE1", "SPI0_CE1_N"}, Caps: embd.CapDigital | embd.CapSPI, DigitalLogical: 7},
}
// This is the same as the Rev 2 for the first 26 pins.
var rev3Pins = append(append(embd.PinMap(nil), rev2Pins...), embd.PinMap{
&embd.PinDesc{ID: "P1_29", Aliases: []string{"5", "GPIO_5"}, Caps: embd.CapDigital, DigitalLogical: 5},
&embd.PinDesc{ID: "P1_31", Aliases: []string{"6", "GPIO_6"}, Caps: embd.CapDigital, DigitalLogical: 6},
&embd.PinDesc{ID: "P1_32", Aliases: []string{"12", "GPIO_12"}, Caps: embd.CapDigital, DigitalLogical: 12},
&embd.PinDesc{ID: "P1_33", Aliases: []string{"13", "GPIO_13"}, Caps: embd.CapDigital, DigitalLogical: 13},
&embd.PinDesc{ID: "P1_35", Aliases: []string{"19", "GPIO_19"}, Caps: embd.CapDigital, DigitalLogical: 19},
&embd.PinDesc{ID: "P1_36", Aliases: []string{"16", "GPIO_16"}, Caps: embd.CapDigital, DigitalLogical: 16},
&embd.PinDesc{ID: "P1_37", Aliases: []string{"26", "GPIO_26"}, Caps: embd.CapDigital, DigitalLogical: 26},
&embd.PinDesc{ID: "P1_38", Aliases: []string{"20", "GPIO_20"}, Caps: embd.CapDigital, DigitalLogical: 20},
&embd.PinDesc{ID: "P1_40", Aliases: []string{"21", "GPIO_21"}, Caps: embd.CapDigital, DigitalLogical: 21},
}...)
var ledMap = embd.LEDMap{
"led0": []string{"0", "led0", "LED0"},
}
func init() {
embd.Register(embd.HostRPi, func(rev int) *embd.Descriptor {
// Refer to http://elinux.org/RPi_HardwareHistory#Board_Revision_History
// for details.
pins := rev3Pins
if rev < 16 {
pins = rev2Pins
}
if rev < 4 {
pins = rev1Pins
}
return &embd.Descriptor{
GPIODriver: func() embd.GPIODriver {
return embd.NewGPIODriver(pins, generic.NewDigitalPin, nil, nil)
},
I2CDriver: func() embd.I2CDriver {
return embd.NewI2CDriver(generic.NewI2CBus)
},
LEDDriver: func() embd.LEDDriver {
return embd.NewLEDDriver(ledMap, generic.NewLED)
},
SPIDriver: func() embd.SPIDriver {
return embd.NewSPIDriver(spiDeviceMinor, generic.NewSPIBus, nil)
},
}
})
}
Loading…
Cancel
Save