kopia lustrzana https://github.com/cariboulabs/cariboulite
Changes in IO utils.
1. removed pigpio 2. moved to using gpiomem api for gpios 3. using spidev for soft-hard spi 4. updated the other parts of software. note: tbd changes in the config.txt of spidev. note: tbd moving out he kernel module to /etc/modules.d to be completely free of sudoing anything firmware rx verificationbug_fixes_integration_tx
rodzic
5c72ea515c
commit
79d5ee11af
|
@ -4,7 +4,9 @@ pcf_file = ./io.pcf
|
|||
|
||||
top.bin:
|
||||
yosys -p 'synth_ice40 -top top -json $(filename).json -blif $(filename).blif' -p 'ice40_opt' -p 'fsm_opt' $(filename).v
|
||||
nextpnr-ice40 --lp1k --package qn84 --json $(filename).json --pcf $(pcf_file) --asc $(filename).asc
|
||||
#nextpnr-ice40 --lp1k --package qn84 --json $(filename).json --pcf $(pcf_file) --asc $(filename).asc
|
||||
nextpnr-ice40 --lp1k --package qn84 --json $(filename).json --pcf $(pcf_file) --asc $(filename).asc --freq 64 --parallel-refine --opt-timing
|
||||
#nextpnr-ice40 --json blinky.json --pcf blinky.pcf --asc blinky.asc --gui
|
||||
icepack $(filename).asc $(filename).bin
|
||||
|
||||
build: top.bin
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
set_frequency w_clock_sys 64
|
||||
set_frequency smi_ctrl_ins.soe_and_reset 16
|
||||
set_frequency i_smi_swe_srw 16
|
||||
#set_frequency lvds_clock_buf 64
|
||||
set_frequency lvds_clock_buf 64
|
||||
set_frequency i_sck 5
|
||||
|
||||
# CLOCK
|
||||
|
|
25340
firmware/top.asc
25340
firmware/top.asc
Plik diff jest za duży
Load Diff
BIN
firmware/top.bin
BIN
firmware/top.bin
Plik binarny nie jest wyświetlany.
Plik diff jest za duży
Load Diff
1356
firmware/top.json
1356
firmware/top.json
Plik diff jest za duży
Load Diff
|
@ -244,7 +244,6 @@ module top (
|
|||
.D_IN_1(w_lvds_rx_24_d1)
|
||||
); // the 180 deg data output
|
||||
|
||||
|
||||
// TODO!!!: w_lvds_rx_24_d1's route reports long routing. We need to put a register between it and the
|
||||
// Consumer: lvds_rx_24_inst
|
||||
|
||||
|
@ -288,6 +287,8 @@ module top (
|
|||
.D_OUT_1(w_lvds_tx_d0)
|
||||
);
|
||||
|
||||
// Logic on a clock signal is very bad - try to use a dedicated
|
||||
// SB_IO
|
||||
assign o_iq_tx_clk_p = lvds_clock_buf;
|
||||
assign o_iq_tx_clk_n = ~lvds_clock_buf;
|
||||
|
||||
|
|
|
@ -167,7 +167,7 @@ int at86rf215_init(at86rf215_st* dev,
|
|||
|
||||
ZF_LOGI("Adding chip definition to io_utils_spi");
|
||||
io_utils_hard_spi_st hard_dev_modem = { .spi_dev_id = dev->spi_dev, .spi_dev_channel = dev->spi_channel, };
|
||||
dev->io_spi_handle = io_utils_spi_add_chip(dev->io_spi, dev->cs_pin, 5000000, 0, 0,
|
||||
dev->io_spi_handle = io_utils_spi_add_chip(dev->io_spi, dev->cs_pin, 2000000, 0, 0,
|
||||
io_utils_spi_chip_type_modem,
|
||||
&hard_dev_modem);
|
||||
|
||||
|
|
|
@ -10,6 +10,7 @@
|
|||
|
||||
#define FPGA_RESET 26
|
||||
#define ICE40_CS 18
|
||||
#define MIXER_RESET 5
|
||||
#define CARIBOULITE_SPI_DEV 1
|
||||
#define CARIBOULITE_MODEM_SPI_CHANNEL 1
|
||||
|
||||
|
@ -204,7 +205,7 @@ int test_at86rf215_continues_iq_loopback (at86rf215_st* dev, at86rf215_rf_channe
|
|||
// -----------------------------------------------------------------------------------------
|
||||
// TEST SELECTION
|
||||
// -----------------------------------------------------------------------------------------
|
||||
#define NO_FPGA_MODE 0
|
||||
#define NO_FPGA_MODE 1
|
||||
#define TEST_VERSIONS 1
|
||||
#define TEST_FREQ_SWEEP 0
|
||||
#define TEST_IQ_RX_WIND 1
|
||||
|
@ -221,7 +222,7 @@ int main ()
|
|||
at86rf215_irq_st irq = {0};
|
||||
|
||||
// Init GPIOs and set FPGA on reset
|
||||
io_utils_setup(NULL);
|
||||
io_utils_setup();
|
||||
|
||||
#if NO_FPGA_MODE
|
||||
// When the FPGA wakes up non-programmed, it starts interogating
|
||||
|
@ -234,6 +235,9 @@ int main ()
|
|||
io_utils_set_gpio_mode(ICE40_CS, io_utils_alt_gpio_out);
|
||||
io_utils_write_gpio(FPGA_RESET, 0);
|
||||
io_utils_write_gpio(ICE40_CS, 0);
|
||||
|
||||
io_utils_set_gpio_mode(MIXER_RESET, io_utils_alt_gpio_out);
|
||||
io_utils_write_gpio(MIXER_RESET, 0);
|
||||
#endif
|
||||
|
||||
// Init spi
|
||||
|
@ -241,6 +245,8 @@ int main ()
|
|||
|
||||
at86rf215_reset(&dev);
|
||||
at86rf215_init(&dev, &io_spi_dev);
|
||||
|
||||
io_utils_spi_print_setup(&io_spi_dev);
|
||||
|
||||
test_at86rf215_read_all_regs_check(&dev);
|
||||
|
||||
|
|
|
@ -17,14 +17,14 @@ extern "C" {
|
|||
|
||||
/*
|
||||
* Time tagging of the module through the 'struct tm' structure
|
||||
* Date: 2023-05-30
|
||||
* Time: 17:04:29
|
||||
* Date: 2023-05-31
|
||||
* Time: 13:29:01
|
||||
*/
|
||||
struct tm smi_stream_dev_date_time = {
|
||||
.tm_sec = 29,
|
||||
.tm_min = 4,
|
||||
.tm_hour = 17,
|
||||
.tm_mday = 30,
|
||||
.tm_sec = 1,
|
||||
.tm_min = 29,
|
||||
.tm_hour = 13,
|
||||
.tm_mday = 31,
|
||||
.tm_mon = 4, /* +1 */
|
||||
.tm_year = 123, /* +1900 */
|
||||
};
|
||||
|
|
|
@ -202,7 +202,7 @@ static int cariboulite_setup_signals(sys_st *sys)
|
|||
int cariboulite_setup_io (sys_st* sys)
|
||||
{
|
||||
ZF_LOGI("Setting up board I/Os");
|
||||
if (io_utils_setup(NULL) < 0)
|
||||
if (io_utils_setup() < 0)
|
||||
{
|
||||
ZF_LOGE("Error setting up io_utils");
|
||||
return -1;
|
||||
|
|
|
@ -9,7 +9,9 @@ include_directories(${SUPER_DIR})
|
|||
|
||||
#However, the file(GLOB...) allows for wildcard additions:
|
||||
set(SOURCES_LIB io_utils.c io_utils_spi.c io_utils_sys_info.c io_utils_fs.c io_utils_i2c.c)
|
||||
set(SOURCES_PIG_LIB pigpio/pigpio.c pigpio/command.c)
|
||||
#set(SOURCES_PIG_LIB pigpio/pigpio.c pigpio/command.c)
|
||||
set(SOURCES_RPI_LIB rpi/rpi.c)
|
||||
set(SOURCES_SPIDEV_LIB spidev/spi.c)
|
||||
set(EXTERN_LIBS ${SUPER_DIR}/zf_log/build/libzf_log.a)
|
||||
#add_compile_options(-Wall -Wextra -pedantic -Werror)
|
||||
#add_compile_options(-Wall -Wextra)
|
||||
|
@ -20,7 +22,8 @@ set(THREADS_PREFER_PTHREAD_FLAG TRUE)
|
|||
find_package(Threads REQUIRED)
|
||||
|
||||
#Generate the static library from the sources
|
||||
add_library(io_utils STATIC ${SOURCES_LIB} ${SOURCES_PIG_LIB})
|
||||
#add_library(io_utils STATIC ${SOURCES_LIB} ${SOURCES_PIG_LIB})
|
||||
add_library(io_utils STATIC ${SOURCES_LIB} ${SOURCES_RPI_LIB} ${SOURCES_SPIDEV_LIB})
|
||||
target_include_directories(io_utils PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
target_link_libraries(io_utils PRIVATE pthread)
|
||||
|
||||
|
|
|
@ -6,7 +6,7 @@
|
|||
#define ZF_LOG_TAG "IO_UTILS_Main"
|
||||
|
||||
#include <time.h>
|
||||
#include "pigpio/pigpio.h"
|
||||
//#include "pigpio/pigpio.h"
|
||||
#include "zf_log/zf_log.h"
|
||||
#include "io_utils.h"
|
||||
|
||||
|
@ -14,87 +14,65 @@
|
|||
// DEFINITIONS
|
||||
|
||||
// STATIC VARIABLES
|
||||
//static uint32_t *gpio_map;
|
||||
static char *io_utils_gpio_mode_strs[] = {"IN","OUT","ALT5","ALT4","ALT0","ALT1","ALT2","ALT3"};
|
||||
|
||||
// STATIC FUNCTIONS
|
||||
#define IO_UTILS_SHORT_WAIT(N) {for (int i=0; i<(N); i++) { asm volatile("nop"); }}
|
||||
|
||||
//=============================================================================================
|
||||
int io_utils_setup(pigpioSigHandler sigHandler)
|
||||
int io_utils_setup()
|
||||
{
|
||||
ZF_LOGI("initializing pigpio");
|
||||
gpioCfgInterfaces(PI_DISABLE_FIFO_IF | PI_DISABLE_SOCK_IF | PI_LOCALHOST_SOCK_IF);
|
||||
ZF_LOGI("initializing rpi");
|
||||
|
||||
int cfg = gpioCfgGetInternals();
|
||||
cfg |= PI_CFG_NOSIGHANDLER;
|
||||
gpioCfgSetInternals(cfg);
|
||||
rpi_init(0);
|
||||
|
||||
int status = gpioInitialise();
|
||||
if (status < 0)
|
||||
{
|
||||
ZF_LOGE("initializing pigpio failed");
|
||||
return -1;
|
||||
}
|
||||
ZF_LOGI("pigpio version %d", status);
|
||||
|
||||
if (sigHandler != NULL)
|
||||
{
|
||||
change_sigaction_unhandled_condition(sigHandler);
|
||||
}
|
||||
return 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
//=============================================================================================
|
||||
void io_utils_cleanup()
|
||||
{
|
||||
gpioTerminate();
|
||||
rpi_close();
|
||||
}
|
||||
|
||||
//=============================================================================================
|
||||
inline void io_utils_set_pullupdn(int gpio, io_utils_pull_en pud)
|
||||
{
|
||||
gpioSetPullUpDown(gpio, pud);
|
||||
gpio_enable_pud(gpio, pud);
|
||||
}
|
||||
|
||||
//=============================================================================================
|
||||
inline void io_utils_setup_gpio(int gpio, io_utils_dir_en direction, io_utils_pull_en pud)
|
||||
{
|
||||
io_utils_set_pullupdn(gpio, pud);
|
||||
io_utils_set_gpio_mode(gpio, direction);
|
||||
io_utils_set_pullupdn(gpio, pud);
|
||||
io_utils_set_gpio_mode(gpio, direction);
|
||||
}
|
||||
|
||||
//=============================================================================================
|
||||
char* io_utils_get_alt_from_mode(io_utils_alt_en mode)
|
||||
{
|
||||
return io_utils_gpio_mode_strs[mode];
|
||||
return io_utils_gpio_mode_strs[mode];
|
||||
}
|
||||
|
||||
//=============================================================================================
|
||||
inline int io_utils_get_gpio_mode(int gpio, int print)
|
||||
{
|
||||
int value = gpioGetMode(gpio);
|
||||
{
|
||||
int value = get_gpio_config(gpio);
|
||||
|
||||
if (print) printf("GPIO #%d, mode: %s (%d)\n", gpio, io_utils_gpio_mode_strs[value], value);
|
||||
return value;
|
||||
if (print) printf("GPIO #%d, mode: %s (%d)\n", gpio, io_utils_gpio_mode_strs[value], value);
|
||||
return value;
|
||||
}
|
||||
|
||||
//=============================================================================================
|
||||
inline void io_utils_set_gpio_mode(int gpio, io_utils_alt_en mode)
|
||||
{
|
||||
if (gpioSetMode(gpio, mode) < 0)
|
||||
{
|
||||
ZF_LOGE("couldn't set mode for gpio %d", gpio);
|
||||
}
|
||||
gpio_config(gpio, mode);
|
||||
}
|
||||
|
||||
//=============================================================================================
|
||||
inline void io_utils_write_gpio(int gpio, int value)
|
||||
{
|
||||
if (gpioWrite(gpio, value) < 0)
|
||||
{
|
||||
ZF_LOGE("couldn't write to gpio %d", gpio);
|
||||
}
|
||||
gpio_write(gpio, value);
|
||||
}
|
||||
|
||||
//=============================================================================================
|
||||
|
@ -110,28 +88,28 @@ void io_utils_write_gpio_with_wait(int gpio, int value, int nopcnt)
|
|||
//=============================================================================================
|
||||
int io_utils_wait_gpio_state(int gpio, int state, int cnt)
|
||||
{
|
||||
while(io_utils_read_gpio(gpio) == !state && cnt--)
|
||||
{
|
||||
io_utils_usleep(100000);
|
||||
}
|
||||
if (cnt <= 0)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
return 0;
|
||||
while(io_utils_read_gpio(gpio) == !state && cnt--)
|
||||
{
|
||||
io_utils_usleep(100000);
|
||||
}
|
||||
if (cnt <= 0)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
//=============================================================================================
|
||||
inline int io_utils_read_gpio(int gpio)
|
||||
{
|
||||
return gpioRead(gpio);
|
||||
return gpio_read(gpio);
|
||||
}
|
||||
|
||||
//=============================================================================================
|
||||
void io_utils_usleep(int usec)
|
||||
{
|
||||
struct timespec req = {.tv_sec = 0, .tv_nsec = usec * 1000L};
|
||||
nanosleep(&req, (struct timespec *)NULL);
|
||||
struct timespec req = {.tv_sec = 0, .tv_nsec = usec * 1000L};
|
||||
nanosleep(&req, (struct timespec *)NULL);
|
||||
}
|
||||
|
||||
//=============================================================================================
|
||||
|
@ -139,5 +117,5 @@ inline int io_utils_setup_interrupt(int gpio,
|
|||
gpioAlertFuncEx_t cb,
|
||||
void* context)
|
||||
{
|
||||
return gpioSetAlertFuncEx(gpio, cb, context);
|
||||
return 0; //gpioSetAlertFuncEx(gpio, cb, context);
|
||||
}
|
||||
|
|
|
@ -9,7 +9,8 @@ extern "C" {
|
|||
#include <string.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include "pigpio/pigpio.h"
|
||||
#include "rpi/rpi.h"
|
||||
//#include "pigpio/pigpio.h"
|
||||
|
||||
typedef enum
|
||||
{
|
||||
|
@ -36,8 +37,8 @@ typedef enum
|
|||
io_utils_alt_5 = 2,
|
||||
} io_utils_alt_en;
|
||||
|
||||
int io_utils_setup(pigpioSigHandler sigHandler);
|
||||
void io_utils_cleanup();
|
||||
int io_utils_setup(void);
|
||||
void io_utils_cleanup(void);
|
||||
void io_utils_set_pullupdn(int gpio, io_utils_pull_en pud);
|
||||
void io_utils_setup_gpio(int gpio, io_utils_dir_en direction, io_utils_pull_en pud);
|
||||
int io_utils_get_gpio_mode(int gpio, int print);
|
||||
|
@ -47,9 +48,13 @@ void io_utils_write_gpio_with_wait(int gpio, int value, int nopcnt);
|
|||
int io_utils_wait_gpio_state(int gpio, int state, int cnt);
|
||||
int io_utils_read_gpio(int gpio);
|
||||
char* io_utils_get_alt_from_mode(io_utils_alt_en mode);
|
||||
|
||||
// for compliance
|
||||
typedef void (*gpioAlertFuncEx_t) (int gpio, int level, uint32_t tick, void *userdata);
|
||||
int io_utils_setup_interrupt( int gpio,
|
||||
gpioAlertFuncEx_t cb,
|
||||
void* context);
|
||||
|
||||
void io_utils_usleep(int usec);
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
|
|
@ -12,6 +12,7 @@
|
|||
#include "zf_log/zf_log.h"
|
||||
#include "io_utils_spi.h"
|
||||
#include "io_utils.h"
|
||||
#include "spidev/spi.h"
|
||||
|
||||
static char *io_utils_chip_types[] =
|
||||
{
|
||||
|
@ -307,7 +308,7 @@ int io_utils_spi_init(io_utils_spi_st* dev)
|
|||
// initialize the hard handles
|
||||
for (int i = 0; i < IO_UTILS_MAX_CHIPS; i++)
|
||||
{
|
||||
dev->chips[i].hard_spi_handle = -1;
|
||||
dev->chips[i].is_hard_spi = 0;
|
||||
dev->chips[i].initialized = 0;
|
||||
}
|
||||
|
||||
|
@ -361,12 +362,9 @@ int io_utils_spi_close(io_utils_spi_st* dev)
|
|||
// now terminate all used spi channels
|
||||
for (int i = 0; i < dev->num_of_chips; i++)
|
||||
{
|
||||
if (dev->chips[i].hard_spi_handle >=0)
|
||||
if (dev->chips[i].is_hard_spi)
|
||||
{
|
||||
if (spiClose(dev->chips[i].hard_spi_handle) < 0)
|
||||
{
|
||||
ZF_LOGE("pigpio says %d is a BAD HANDLE", dev->chips[i].hard_spi_handle);
|
||||
}
|
||||
spi_free(&dev->chips[i].hard_dev.spidev);
|
||||
}
|
||||
dev->chips[i].initialized = 0;
|
||||
}
|
||||
|
@ -415,25 +413,33 @@ int io_utils_spi_add_chip(io_utils_spi_st* dev, int cs_pin, int speed, int swap_
|
|||
dev->chips[new_chip_index].cs_pin = cs_pin;
|
||||
dev->chips[new_chip_index].miso_mosi_swap = swap_mi_mo;
|
||||
dev->chips[new_chip_index].chip_type = chip_type;
|
||||
dev->chips[new_chip_index].is_hard_spi = 0;
|
||||
|
||||
// now lets check if we need a hard spi handle (not a bitbanged configuration)
|
||||
if (chip_type == io_utils_spi_chip_type_fpga_comm ||
|
||||
chip_type == io_utils_spi_chip_type_modem)
|
||||
{
|
||||
memcpy (&dev->chips[new_chip_index].hard_dev, hard_dev, sizeof(io_utils_hard_spi_st));
|
||||
unsigned int spiFlags = ((dev->chips[new_chip_index].hard_dev.spi_dev_id&0x1)<<8);
|
||||
|
||||
res = spiOpen(dev->chips[new_chip_index].hard_dev.spi_dev_channel, speed, spiFlags);
|
||||
char spi_device_file[32];
|
||||
sprintf(spi_device_file, "/dev/spidev%d.%d", hard_dev->spi_dev_id, hard_dev->spi_dev_channel);
|
||||
|
||||
res = spi_init(&dev->chips[new_chip_index].hard_dev.spidev,
|
||||
spi_device_file, // filename like "/dev/spidev0.0"
|
||||
mode, // SPI_* (look "linux/spi/spidev.h")
|
||||
0, // bits per word (usually 8)
|
||||
speed); // max speed [Hz]
|
||||
if (res < 0)
|
||||
{
|
||||
ZF_LOGE("spiOpen function failed with code %d", res);
|
||||
ZF_LOGE("spi_init function failed with code %d, (%s)", res, spi_get_code_desc(res));
|
||||
pthread_mutex_unlock(&dev->mtx);
|
||||
return -1;
|
||||
}
|
||||
|
||||
dev->chips[new_chip_index].is_hard_spi = 1;
|
||||
}
|
||||
|
||||
dev->chips[new_chip_index].hard_spi_handle = res;
|
||||
dev->chips[new_chip_index].initialized = 1;
|
||||
|
||||
// finally increase the number of chips
|
||||
dev->num_of_chips += 1;
|
||||
|
||||
|
@ -492,11 +498,7 @@ int io_utils_spi_remove_chip(io_utils_spi_st* dev, int chip_handle)
|
|||
if (dev->chips[chip_handle].chip_type == io_utils_spi_chip_type_fpga_comm ||
|
||||
dev->chips[chip_handle].chip_type == io_utils_spi_chip_type_modem)
|
||||
{
|
||||
if (spiClose(dev->chips[chip_handle].hard_spi_handle) < 0)
|
||||
{
|
||||
ZF_LOGE("the specified hard_handle - %d - is not valid", dev->chips[chip_handle].hard_spi_handle);
|
||||
// no return as we anyway are going to return
|
||||
}
|
||||
spi_free(&dev->chips[chip_handle].hard_dev.spidev);
|
||||
}
|
||||
dev->chips[chip_handle].initialized = 0;
|
||||
dev->num_of_chips -= 1;
|
||||
|
@ -544,13 +546,9 @@ int io_utils_spi_transmit(io_utils_spi_st* dev, int chip_handle,
|
|||
case io_utils_spi_chip_type_modem:
|
||||
{
|
||||
//printf("SPI XFER chiptype = %d\n", dev->current_chip->chip_type);
|
||||
|
||||
// a regular spi communication
|
||||
ret = spiXfer(dev->current_chip->hard_spi_handle, (char*)tx_buf, (char*)rx_buf, length);
|
||||
if (set_up_hard)
|
||||
{
|
||||
// workaround pigpio problem
|
||||
ret = spiXfer(dev->current_chip->hard_spi_handle, (char*)tx_buf, (char*)rx_buf, length);
|
||||
}
|
||||
ret = spi_exchange(&dev->current_chip->hard_dev.spidev, (char*)rx_buf, (char*)tx_buf, length);
|
||||
if (ret < 0)
|
||||
{
|
||||
ZF_LOGE("spi transfer failed (%d)", ret);
|
||||
|
@ -645,8 +643,8 @@ void io_utils_spi_print_setup(io_utils_spi_st* dev)
|
|||
printf(" MISO / MOSI swap: %d\n", dev->chips[i].miso_mosi_swap);
|
||||
printf(" Chip type: %s (%d)\n", io_utils_chip_types[dev->chips[i].chip_type],
|
||||
dev->chips[i].chip_type);
|
||||
printf(" Hard spi handle: %d\n", dev->chips[i].hard_spi_handle);
|
||||
if (dev->chips[i].hard_spi_handle>=0)
|
||||
printf(" Is hard SPI: %d\n", dev->chips[i].is_hard_spi);
|
||||
if (dev->chips[i].is_hard_spi)
|
||||
{
|
||||
printf(" Hard spi id: %d\n", dev->chips[i].hard_dev.spi_dev_id);
|
||||
printf(" Hard spi channel: %d\n", dev->chips[i].hard_dev.spi_dev_channel);
|
||||
|
|
|
@ -10,6 +10,7 @@ extern "C" {
|
|||
#include <stdbool.h>
|
||||
#include <pthread.h>
|
||||
#include "io_utils.h"
|
||||
#include "spidev/spi.h"
|
||||
|
||||
|
||||
#define IO_UTILS_MAX_CHIPS 10
|
||||
|
@ -34,6 +35,7 @@ typedef struct
|
|||
{
|
||||
int spi_dev_id; // either spidev0 or spidev1
|
||||
int spi_dev_channel; // the channel number (2 cs for spidev0, 3 cs of spidev1)
|
||||
spi_t spidev;
|
||||
} io_utils_hard_spi_st;
|
||||
|
||||
typedef struct
|
||||
|
@ -46,7 +48,7 @@ typedef struct
|
|||
|
||||
int initialized;
|
||||
io_utils_spi_chip_type_en chip_type;
|
||||
int hard_spi_handle;
|
||||
int is_hard_spi;
|
||||
} io_utils_spi_chip_st;
|
||||
|
||||
typedef struct
|
||||
|
|
|
@ -38,25 +38,40 @@ int main(int argc, char *argv[])
|
|||
io_utils_sys_info_st info = {0};
|
||||
io_utils_get_rpi_info(&info);
|
||||
|
||||
//printf("----------------------------------------------------\n");
|
||||
//printf("RPI information\n");
|
||||
//io_utils_print_rpi_info(&info);
|
||||
printf("----------------------------------------------------\n");
|
||||
printf("RPI information\n");
|
||||
io_utils_print_rpi_info(&info);
|
||||
|
||||
printf("----------------------------------------------------\n");
|
||||
printf("GPIO Init\n");
|
||||
io_utils_setup(NULL);
|
||||
io_utils_setup();
|
||||
// Reset the FPGA
|
||||
//io_utils_set_gpio_mode(FPGA_RESET, io_utils_alt_gpio_out);
|
||||
//io_utils_set_gpio_mode(ICE40_CS, io_utils_alt_gpio_out);
|
||||
//io_utils_write_gpio(FPGA_RESET, 0);
|
||||
//io_utils_write_gpio(ICE40_CS, 0);
|
||||
|
||||
// setup the addresses
|
||||
io_utils_set_gpio_mode(2, io_utils_alt_1); // addr
|
||||
io_utils_set_gpio_mode(3, io_utils_alt_1); // addr
|
||||
|
||||
// Setup the bus I/Os
|
||||
// --------------------------------------------
|
||||
for (int i = 6; i <= 15; i++)
|
||||
{
|
||||
io_utils_set_gpio_mode(i, io_utils_alt_1); // 8xData + SWE + SOE
|
||||
}
|
||||
|
||||
io_utils_set_gpio_mode(24, io_utils_alt_1); // rwreq
|
||||
io_utils_set_gpio_mode(25, io_utils_alt_1); // rwreq
|
||||
|
||||
|
||||
for (int i = 0; i < 28; i ++)
|
||||
{
|
||||
io_utils_get_gpio_mode(i, 1);
|
||||
}
|
||||
|
||||
printf("----------------------------------------------------\n");
|
||||
/*printf("----------------------------------------------------\n");
|
||||
printf("SPI Init\n");
|
||||
io_utils_spi_init(&spi_dev);
|
||||
|
||||
|
@ -94,29 +109,29 @@ int main(int argc, char *argv[])
|
|||
//printf("FPGA: Sent %02X, %02X, Received: %02X, %02X\n", *(tx_buf+i), *(tx_buf+i+1), rx_buf[0], rx_buf[1]);
|
||||
}
|
||||
|
||||
/*for (int i = 0; i < 10; i++)
|
||||
{
|
||||
io_utils_spi_transmit(&spi_dev, hspi_mixer, tx_buf+i, rx_buf, 3, io_utils_spi_write);
|
||||
io_utils_spi_transmit(&spi_dev, hspi_mixer, tx_buf+i, rx_buf, 3, io_utils_spi_read);
|
||||
//printf("MIXER: Sent %02X, %02X, %02X, Received: %02X, %02X\n",
|
||||
// *(tx_buf+i), *(tx_buf+i+1), *(tx_buf+i+2), rx_buf[0], rx_buf[1]);
|
||||
}*/
|
||||
/*
|
||||
for (int i = 0; i < 10; i++)
|
||||
{
|
||||
io_utils_spi_transmit(&spi_dev, hspi_modem, tx_buf+i, rx_buf, 2, io_utils_spi_read_write);
|
||||
//printf("FPGA: Sent %02X, %02X, Received: %02X, %02X\n", *(tx_buf+i), *(tx_buf+i+1), rx_buf[0], rx_buf[1]);
|
||||
}*/
|
||||
//for (int i = 0; i < 10; i++)
|
||||
//{
|
||||
// io_utils_spi_transmit(&spi_dev, hspi_mixer, tx_buf+i, rx_buf, 3, io_utils_spi_write);
|
||||
// io_utils_spi_transmit(&spi_dev, hspi_mixer, tx_buf+i, rx_buf, 3, io_utils_spi_read);
|
||||
// //printf("MIXER: Sent %02X, %02X, %02X, Received: %02X, %02X\n",
|
||||
// // *(tx_buf+i), *(tx_buf+i+1), *(tx_buf+i+2), rx_buf[0], rx_buf[1]);
|
||||
//}
|
||||
|
||||
//for (int i = 0; i < 10; i++)
|
||||
//{
|
||||
// io_utils_spi_transmit(&spi_dev, hspi_modem, tx_buf+i, rx_buf, 2, io_utils_spi_read_write);
|
||||
// //printf("FPGA: Sent %02X, %02X, Received: %02X, %02X\n", *(tx_buf+i), *(tx_buf+i+1), rx_buf[0], rx_buf[1]);
|
||||
//}
|
||||
}
|
||||
|
||||
/*for (int i = 0; i < 10; i++)
|
||||
{
|
||||
io_utils_spi_transmit(&spi_dev, hspi_mixer, tx_buf+i, rx_buf, 3, io_utils_spi_read);
|
||||
printf("MIXER: Requested Reg %02X, Received: %02X, %02X\n",
|
||||
*(tx_buf+i), rx_buf[0], rx_buf[1]);
|
||||
}*/
|
||||
//for (int i = 0; i < 10; i++)
|
||||
//{
|
||||
// io_utils_spi_transmit(&spi_dev, hspi_mixer, tx_buf+i, rx_buf, 3, io_utils_spi_read);
|
||||
// printf("MIXER: Requested Reg %02X, Received: %02X, %02X\n",
|
||||
// *(tx_buf+i), rx_buf[0], rx_buf[1]);
|
||||
//}
|
||||
|
||||
io_utils_spi_close(&spi_dev);
|
||||
io_utils_spi_close(&spi_dev);*/
|
||||
io_utils_cleanup();
|
||||
}
|
||||
|
||||
|
|
|
@ -7344,6 +7344,7 @@ static int initGrabLockFile(void)
|
|||
if (fd != -1)
|
||||
{
|
||||
lockResult = flock(fd, LOCK_EX|LOCK_NB);
|
||||
SOFT_ERROR(PI_INIT_FAILED, "flock failed");
|
||||
|
||||
if(lockResult == 0)
|
||||
{
|
||||
|
|
Plik diff jest za duży
Load Diff
|
@ -0,0 +1,148 @@
|
|||
/**
|
||||
* rpi.h
|
||||
*
|
||||
* Copyright (c) 2017 Ed Alegrid <ealegrid@gmail.com>
|
||||
* GNU General Public License v3.0
|
||||
*
|
||||
*/
|
||||
|
||||
/* Defines for RPI */
|
||||
#ifndef RPI_H
|
||||
#define RPI_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#define RPI_VERSION 100
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
|
||||
/* Initialize RPI library */
|
||||
extern void rpi_init(int access);
|
||||
|
||||
/* Close RPI library */
|
||||
extern uint8_t rpi_close();
|
||||
|
||||
/**
|
||||
* Time Delays
|
||||
*/
|
||||
void nswait(uint64_t ns); //nanosecond time delay
|
||||
|
||||
void uswait(uint32_t us); //microsecond time delay
|
||||
|
||||
void mswait(uint32_t ms); //millisecond time delay
|
||||
|
||||
/**
|
||||
* GPIO
|
||||
*/
|
||||
void gpio_config(uint8_t pin, uint8_t mode);
|
||||
|
||||
uint8_t get_gpio_config(uint8_t pin);
|
||||
|
||||
void gpio_input(uint8_t pin);
|
||||
|
||||
void gpio_output(uint8_t pin);
|
||||
|
||||
uint8_t gpio_read(uint8_t pin);
|
||||
|
||||
uint8_t gpio_write(uint8_t pin, uint8_t bit);
|
||||
|
||||
void gpio_on(uint8_t pin);
|
||||
|
||||
void gpio_off(uint8_t pin);
|
||||
|
||||
void gpio_pulse(uint8_t pin, int td);
|
||||
|
||||
void gpio_reset_all_events(uint8_t pin);
|
||||
|
||||
void gpio_enable_high_event(uint8_t pin, uint8_t bit);
|
||||
|
||||
void gpio_enable_low_event(uint8_t pin, uint8_t bit);
|
||||
|
||||
void gpio_enable_rising_event(uint8_t pin, uint8_t bit);
|
||||
|
||||
void gpio_enable_falling_event(uint8_t pin, uint8_t bit);
|
||||
|
||||
void gpio_enable_async_rising_event(uint8_t pin, uint8_t bit);
|
||||
|
||||
void gpio_enable_async_falling_event(uint8_t pin, uint8_t bit);
|
||||
|
||||
uint8_t gpio_detect_input_event(uint8_t pin);
|
||||
|
||||
void gpio_reset_event(uint8_t pin);
|
||||
|
||||
void gpio_enable_pud(uint8_t pin, uint8_t value);
|
||||
|
||||
/**
|
||||
* PWM
|
||||
*/
|
||||
void pwm_set_pin(uint8_t pin);
|
||||
|
||||
void pwm_reset_pin(uint8_t pin);
|
||||
|
||||
void pwm_reset_all_pins();
|
||||
|
||||
uint8_t pwm_set_clock_freq(uint32_t divider);
|
||||
|
||||
uint8_t pwm_clk_status();
|
||||
|
||||
void pwm_enable(uint8_t pin, uint8_t n);
|
||||
|
||||
void pwm_set_mode(uint8_t pin, uint8_t n);
|
||||
|
||||
void pwm_set_pola(uint8_t pin, uint8_t n);
|
||||
|
||||
void pwm_set_data(uint8_t pin, uint32_t data);
|
||||
|
||||
void pwm_set_range(uint8_t pin, uint32_t range);
|
||||
|
||||
/**
|
||||
* I2C
|
||||
*/
|
||||
int i2c_start();
|
||||
|
||||
int i2c_init(uint8_t value);
|
||||
|
||||
void i2c_stop();
|
||||
|
||||
void i2c_select_slave(uint8_t addr);
|
||||
|
||||
void i2c_set_clock_freq(uint16_t divider);
|
||||
|
||||
void i2c_data_transfer_speed(uint32_t baud);
|
||||
|
||||
uint8_t i2c_write(const char * wbuf, uint8_t len);
|
||||
|
||||
uint8_t i2c_read(char * rbuf, uint8_t len);
|
||||
|
||||
uint8_t i2c_byte_read();
|
||||
|
||||
/**
|
||||
* SPI
|
||||
*/
|
||||
int spi_start();
|
||||
|
||||
void spi_stop();
|
||||
|
||||
void spi_set_clock_freq(uint16_t divider);
|
||||
|
||||
void spi_set_data_mode(uint8_t mode);
|
||||
|
||||
void spi_set_chip_select_polarity(uint8_t cs, uint8_t active);
|
||||
|
||||
void spi_chip_select(uint8_t cs);
|
||||
|
||||
void spi_data_transfer(char* wbuf, char* rbuf, uint8_t len);
|
||||
|
||||
void _spi_write(char* wbuf, uint8_t len);
|
||||
|
||||
void _spi_read(char* rbuf, uint8_t len);
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* RPI_H */
|
|
@ -0,0 +1,285 @@
|
|||
/*
|
||||
* Simple Linux wrapper for access to /dev/spidev
|
||||
* File: "spi.c"
|
||||
* Credit: Alex Zorg (@azorg) @ https://github.com/azorg/spi/blob/master/spi.c
|
||||
*/
|
||||
|
||||
//-----------------------------------------------------------------------------
|
||||
#include "spi.h"
|
||||
//-----------------------------------------------------------------------------
|
||||
#include <unistd.h> // close()
|
||||
#include <string.h> // memset()
|
||||
#include <stdio.h>
|
||||
#include <fcntl.h> // open()
|
||||
#include <sys/ioctl.h> // ioctl()
|
||||
//----------------------------------------------------------------------------
|
||||
// open and init SPIdev
|
||||
// * spi_mode may have next mask: SPI_LOOP | SPI_CPHA | SPI_CPOL |
|
||||
// SPI_LSB_FIRST | SPI_CS_HIGH SPI_3WIRE | SPI_NO_CS | SPI_READY
|
||||
// or 0 by zefault
|
||||
int spi_init(spi_t *self,
|
||||
const char *device, // filename like "/dev/spidev0.0"
|
||||
int mode, // SPI_* (look "linux/spi/spidev...")
|
||||
int bits, // bits per word (usually 8)
|
||||
int speed) // max speed [Hz]
|
||||
{
|
||||
// open SPIdev
|
||||
self->fd = open(device, O_RDWR);
|
||||
if (self->fd < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_init(): failed to open the bus");
|
||||
return SPI_ERR_OPEN;
|
||||
}
|
||||
|
||||
// set mode
|
||||
self->mode = (__u8)mode;
|
||||
if (ioctl(self->fd, SPI_IOC_WR_MODE, &self->mode) < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_init(): can't set bus mode");
|
||||
return SPI_ERR_SET_MODE;
|
||||
}
|
||||
|
||||
// get mode
|
||||
if (ioctl(self->fd, SPI_IOC_RD_MODE, &self->mode) < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_init(): can't get bus mode");
|
||||
return SPI_ERR_GET_MODE;
|
||||
}
|
||||
|
||||
// get "LSB first"
|
||||
if (ioctl(self->fd, SPI_IOC_RD_LSB_FIRST, &self->lsb) < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_init(): can't get 'LSB first'");
|
||||
return SPI_ERR_GET_LSB;
|
||||
}
|
||||
|
||||
// set bits per word
|
||||
if (bits)
|
||||
{
|
||||
self->bits = (__u8)bits;
|
||||
if (ioctl(self->fd, SPI_IOC_WR_BITS_PER_WORD, &self->bits) < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_init(): can't set bits per word");
|
||||
return SPI_ERR_SET_BITS;
|
||||
}
|
||||
}
|
||||
|
||||
// get bits per word
|
||||
if (ioctl(self->fd, SPI_IOC_RD_BITS_PER_WORD, &self->bits) < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_init(): can't get bits per word");
|
||||
return SPI_ERR_GET_BITS;
|
||||
}
|
||||
|
||||
// set max speed [Hz]
|
||||
if (speed)
|
||||
{
|
||||
self->speed = (__u32)speed;
|
||||
if (ioctl(self->fd, SPI_IOC_WR_MAX_SPEED_HZ, &self->speed) < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_init(): can't set max speed [Hz]");
|
||||
return SPI_ERR_SET_SPEED;
|
||||
}
|
||||
}
|
||||
|
||||
// get max speed [Hz]
|
||||
if (ioctl(self->fd, SPI_IOC_RD_MAX_SPEED_HZ, &self->speed) < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_init(): can't get max speed [Hz]");
|
||||
return SPI_ERR_SET_SPEED;
|
||||
}
|
||||
|
||||
printf("open device='%s' mode=%d bits=%d lsb=%d max_speed=%d [Hz]", device, (int)self->mode, (int)self->bits, (int)self->lsb, (int)self->speed);
|
||||
|
||||
return SPI_ERR_NONE;
|
||||
}
|
||||
|
||||
int spi_set_mode(spi_t *self, int mode)
|
||||
{
|
||||
// set mode
|
||||
self->mode = (__u8)mode;
|
||||
if (ioctl(self->fd, SPI_IOC_WR_MODE, &self->mode) < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_init(): can't set bus mode");
|
||||
return SPI_ERR_SET_MODE;
|
||||
}
|
||||
|
||||
// get mode
|
||||
if (ioctl(self->fd, SPI_IOC_RD_MODE, &self->mode) < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_init(): can't get bus mode");
|
||||
return SPI_ERR_GET_MODE;
|
||||
}
|
||||
|
||||
SPI_DBG("set mode to=%d, actual=%d", mode, (int)self->mode);
|
||||
|
||||
return SPI_ERR_NONE;
|
||||
}
|
||||
|
||||
int spi_set_speed(spi_t *self, int speed)
|
||||
{
|
||||
|
||||
// set max speed [Hz]
|
||||
self->speed = (__u32)speed;
|
||||
if (ioctl(self->fd, SPI_IOC_WR_MAX_SPEED_HZ, &self->speed) < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_init(): can't set max speed [Hz]");
|
||||
return SPI_ERR_SET_SPEED;
|
||||
}
|
||||
|
||||
// get max speed [Hz]
|
||||
if (ioctl(self->fd, SPI_IOC_RD_MAX_SPEED_HZ, &self->speed) < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_init(): can't get max speed [Hz]");
|
||||
return SPI_ERR_SET_SPEED;
|
||||
}
|
||||
|
||||
SPI_DBG("set speed max_speed=%d [Hz], actual max_speed=%d [Hz]", speed, (int)self->speed);
|
||||
|
||||
return SPI_ERR_NONE;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
// close SPIdev file and free memory
|
||||
void spi_free(spi_t *self)
|
||||
{
|
||||
close(self->fd);
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
// read data from SPIdev
|
||||
int spi_read(spi_t *self, void *rx_buf, int len)
|
||||
{
|
||||
int retv;
|
||||
|
||||
struct spi_ioc_transfer xfer[1] = {0};
|
||||
|
||||
xfer[0].tx_buf = (__u64)0; // output buffer
|
||||
xfer[0].rx_buf = (__u64)rx_buf; // input buffer
|
||||
xfer[0].len = (__u32)len; // length of data to read
|
||||
|
||||
retv = ioctl(self->fd, SPI_IOC_MESSAGE(1), xfer);
|
||||
if (retv < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_read(): ioctl(SPI_IOC_MESSAGE(1)) return %d", retv);
|
||||
return SPI_ERR_READ;
|
||||
}
|
||||
|
||||
return retv;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
// write data to SPIdev
|
||||
int spi_write(spi_t *self, const void *tx_buf, int len)
|
||||
{
|
||||
int retv;
|
||||
|
||||
struct spi_ioc_transfer xfer[1] = {0};
|
||||
|
||||
xfer[0].tx_buf = (__u64)tx_buf; // output buffer
|
||||
xfer[0].rx_buf = (__u64)0; // input buffer
|
||||
xfer[0].len = (__u32)len; // length of data to write
|
||||
|
||||
retv = ioctl(self->fd, SPI_IOC_MESSAGE(1), xfer);
|
||||
if (retv < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_write(): ioctl(SPI_IOC_MESSAGE(1)) return %d", retv);
|
||||
return SPI_ERR_WRITE;
|
||||
}
|
||||
|
||||
return retv;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
// read and write `len` bytes from/to SPIdev
|
||||
int spi_exchange(spi_t *self, void *rx_buf, const void *tx_buf, int len)
|
||||
{
|
||||
int retv;
|
||||
|
||||
struct spi_ioc_transfer xfer[1] = {0};
|
||||
|
||||
xfer[0].tx_buf = (__u64)tx_buf; // output buffer
|
||||
xfer[0].rx_buf = (__u64)rx_buf; // input buffer
|
||||
xfer[0].len = (__u32)len; // length of data to write
|
||||
|
||||
retv = ioctl(self->fd, SPI_IOC_MESSAGE(1), xfer);
|
||||
if (retv < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_exchange(): ioctl(SPI_IOC_MESSAGE(1)) return %d", retv);
|
||||
return SPI_ERR_EXCHANGE;
|
||||
}
|
||||
|
||||
return retv;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
// read data from SPIdev from specific register address
|
||||
int spi_read_reg8(spi_t *self, uint8_t reg_addr, void *rx_buf, int len)
|
||||
{
|
||||
int retv;
|
||||
|
||||
struct spi_ioc_transfer xfer[2] = {0};
|
||||
|
||||
// Write message for register address
|
||||
xfer[0].tx_buf = (__u64)®_addr; // output buffer
|
||||
xfer[0].rx_buf = (__u64)0; // input buffer
|
||||
xfer[0].len = (__u32)sizeof(reg_addr); // length of data to read
|
||||
|
||||
// Write message for rx data
|
||||
xfer[1].tx_buf = (__u64)0; // output buffer
|
||||
xfer[1].rx_buf = (__u64)rx_buf; // input buffer
|
||||
xfer[1].len = (__u32)len; // length of data to read
|
||||
|
||||
retv = ioctl(self->fd, SPI_IOC_MESSAGE(2), xfer);
|
||||
if (retv < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_read_reg8(): ioctl(SPI_IOC_MESSAGE(2)) return %d", retv);
|
||||
return SPI_ERR_READ;
|
||||
}
|
||||
|
||||
return retv;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
// write data to SPIdev to specific register address
|
||||
int spi_write_reg8(spi_t *self, uint8_t reg_addr, const void *tx_buf, int len)
|
||||
{
|
||||
int retv;
|
||||
|
||||
struct spi_ioc_transfer xfer[2] = {0};
|
||||
|
||||
// Write message for register address
|
||||
xfer[0].tx_buf = (__u64)®_addr; // output buffer
|
||||
xfer[0].rx_buf = (__u64)0; // input buffer
|
||||
xfer[0].len = (__u32)sizeof(reg_addr); // length of data to write
|
||||
|
||||
// Write message for tx data
|
||||
xfer[1].tx_buf = (__u64)tx_buf; // output buffer
|
||||
xfer[1].rx_buf = (__u64)0; // input buffer
|
||||
xfer[1].len = (__u32)len; // length of data to write
|
||||
|
||||
retv = ioctl(self->fd, SPI_IOC_MESSAGE(2), xfer);
|
||||
if (retv < 0)
|
||||
{
|
||||
SPI_DBG("error in spi_write_reg8(): ioctl(SPI_IOC_MESSAGE(2)) return %d", retv);
|
||||
return SPI_ERR_WRITE;
|
||||
}
|
||||
|
||||
return retv;
|
||||
}
|
||||
//----------------------------------------------------------------------------
|
||||
// Get error code description
|
||||
static char *io_utils_chip_types[] =
|
||||
{
|
||||
"SPI_ERR_NONE",
|
||||
"SPI_ERR_OPEN",
|
||||
"SPI_ERR_SET_MODE",
|
||||
"SPI_ERR_GET_MODE",
|
||||
"SPI_ERR_GET_LSB",
|
||||
"SPI_ERR_SET_BITS",
|
||||
"SPI_ERR_GET_BITS",
|
||||
"SPI_ERR_SET_SPEED",
|
||||
"SPI_ERR_GET_SPEED",
|
||||
"SPI_ERR_READ",
|
||||
"SPI_ERR_WRITE",
|
||||
"SPI_ERR_EXCHANGE",
|
||||
};
|
||||
|
||||
char* spi_get_code_desc(int err_code)
|
||||
{
|
||||
return io_utils_chip_types[-err_code];
|
||||
}
|
|
@ -0,0 +1,92 @@
|
|||
/*
|
||||
* Simple Linux wrapper for access to /dev/spidev
|
||||
* File: "spi.h"
|
||||
* Credit: Alex Zorg (@azorg) @ https://github.com/azorg/spi/blob/master/spi.h
|
||||
*/
|
||||
|
||||
#ifndef SPI_H
|
||||
#define SPI_H
|
||||
//-----------------------------------------------------------------------------
|
||||
#include <linux/spi/spidev.h>
|
||||
#include <stdint.h>
|
||||
//-----------------------------------------------------------------------------
|
||||
// common error codes (return values)
|
||||
#define SPI_ERR_NONE 0 // no error, success
|
||||
#define SPI_ERR_OPEN -1 // failed to open the bus
|
||||
#define SPI_ERR_SET_MODE -2 // can't set bus mode
|
||||
#define SPI_ERR_GET_MODE -3 // can't get bus mode
|
||||
#define SPI_ERR_GET_LSB -4 // can't get 'LSB first'
|
||||
#define SPI_ERR_SET_BITS -5 // can't set bits per word
|
||||
#define SPI_ERR_GET_BITS -6 // can't get bits per word
|
||||
#define SPI_ERR_SET_SPEED -7 // can't set max speed [Hz]
|
||||
#define SPI_ERR_GET_SPEED -8 // can't get max speed [Hz]
|
||||
#define SPI_ERR_READ -9 // can't read
|
||||
#define SPI_ERR_WRITE -10 // can't write
|
||||
#define SPI_ERR_EXCHANGE -11 // can't read/write
|
||||
|
||||
//----------------------------------------------------------------------------
|
||||
#ifdef SPI_DEBUG
|
||||
# include <stdio.h> // fprintf()
|
||||
# define SPI_DBG(fmt, arg...) fprintf(stderr, "SPI: " fmt "\n", ## arg)
|
||||
#else
|
||||
# define SPI_DBG(fmt, ...) // debug output off
|
||||
#endif // SPI_DEBUG
|
||||
//----------------------------------------------------------------------------
|
||||
// `spi_t` type structure
|
||||
typedef struct spi_ {
|
||||
int fd; // file descriptor: fd = open(filename, O_RDWR);
|
||||
__u32 speed; // speed [Hz]
|
||||
__u8 mode; // SPI mode
|
||||
__u8 lsb; // LSB first
|
||||
__u8 bits; // bits per word
|
||||
} spi_t;
|
||||
//----------------------------------------------------------------------------
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif // __cplusplus
|
||||
//----------------------------------------------------------------------------
|
||||
// open and init SPIdev
|
||||
// * spi_mode may have next mask: SPI_LOOP | SPI_CPHA | SPI_CPOL |
|
||||
// SPI_LSB_FIRST | SPI_CS_HIGH SPI_3WIRE | SPI_NO_CS | SPI_READY
|
||||
// or 0 by zefault
|
||||
int spi_init(spi_t *self,
|
||||
const char *device, // filename like "/dev/spidev0.0"
|
||||
int mode, // SPI_* (look "linux/spi/spidev.h")
|
||||
int bits, // bits per word (usually 8)
|
||||
int speed); // max speed [Hz]
|
||||
//----------------------------------------------------------------------------
|
||||
// sets mode on existing spi
|
||||
int spi_set_mode(spi_t* self, int mode);
|
||||
//----------------------------------------------------------------------------
|
||||
// sets speed on existing spi
|
||||
int spi_set_speed(spi_t* self, int speed);
|
||||
//----------------------------------------------------------------------------
|
||||
// close SPIdev file and free memory
|
||||
void spi_free(spi_t *self);
|
||||
//----------------------------------------------------------------------------
|
||||
// read data from SPIdev
|
||||
int spi_read(spi_t *self, void* rx_buf, int len);
|
||||
//----------------------------------------------------------------------------
|
||||
// write data to SPIdev
|
||||
int spi_write(spi_t *self, const void* tx_buf, int len);
|
||||
//----------------------------------------------------------------------------
|
||||
// read and write `len` bytes from/to SPIdev
|
||||
int spi_exchange(spi_t *self, void* rx_buf, const void* tx_buf, int len);
|
||||
//----------------------------------------------------------------------------
|
||||
// read data from SPIdev from specific register address
|
||||
int spi_read_reg8(spi_t *self, uint8_t reg_addr, void* rx_buf, int len);
|
||||
//----------------------------------------------------------------------------
|
||||
// write data to SPIdev to specific register address
|
||||
int spi_write_reg8(spi_t *self, uint8_t reg_addr, const void* tx_buf, int len);
|
||||
//----------------------------------------------------------------------------
|
||||
// get error code destriprion
|
||||
char* spi_get_code_desc(int err_code);
|
||||
//----------------------------------------------------------------------------
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif // __cplusplus
|
||||
//----------------------------------------------------------------------------
|
||||
#endif // SPI_H
|
||||
|
||||
/*** end of "spi.h" file ***/
|
Ładowanie…
Reference in New Issue