added lvds rx code

bug_fixes_integration_tx
meexmachina 2021-07-07 15:29:32 +03:00
rodzic 04b15a18ba
commit eb699bc363
16 zmienionych plików z 11114 dodań i 5337 usunięć

75
firmware/lvds_rx.v 100644
Wyświetl plik

@ -0,0 +1,75 @@
module lvds_rx
(
input i_reset,
input i_ddr_clk,
input [1:0] i_ddr_data,
input i_fifo_full,
output o_fifo_write_clk,
output o_fifo_push,
output [31:0] o_fifo_data );
// Internal FSM States
localparam
state_idle = 3'b000,
state_i_phase = 3'b001,
state_q_phase = 3'b010;
// Internal Registers
reg [2:0] r_state_if;
reg [2:0] r_phase_count;
reg [31:0] r_data;
reg r_push;
// Initial conditions
initial begin
r_state_if = state_idle;
r_push = 1'b0;
r_phase_count = 3'b111;
r_data = 0;
end
// Global Assignments
assign o_fifo_push = r_push;
assign o_fifo_data = r_data;
assign o_fifo_write_clk = i_ddr_clk;
// Main Process
always @(negedge i_ddr_clk)
begin
case (r_state_if)
state_idle: begin
if (i_ddr_data == 2'b10 ) begin
r_state_if <= state_i_phase;
r_data <= 0; // may be redundant as we do a full loop
end
r_phase_count <= 3'b111;
r_push <= 1'b0;
end
state_i_phase: begin
if (r_phase_count == 3'b000) begin
r_phase_count <= 3'b111;
r_state_if <= state_q_phase;
r_data <= {r_data[29:0], 2'b00};
end else begin
r_phase_count <= r_phase_count - 1;
r_data <= {r_data[29:0], i_ddr_data};
end
end
state_q_phase: begin
if (r_phase_count == 3'b001) begin
r_push <= ~i_fifo_full;
r_phase_count <= 3'b000;
r_state_if <= state_idle;
end else begin
r_phase_count <= r_phase_count - 1;
end
r_data <= {r_data[29:0], i_ddr_data};
end
endcase
end
endmodule // smi_ctrl

181
firmware/ref_rx.vhd 100644
Wyświetl plik

@ -0,0 +1,181 @@
library IEEE;
use IEEE.STD_LOGIC_1164.ALL;
use IEEE.STD_LOGIC_UNSIGNED.ALL;
use IEEE.NUMERIC_STD.ALL;
library UNISIM;
use UNISIM.VComponents.all;
entity at86rf215_rx_interface is
Port (
reset_n : in STD_LOGIC;
rxd_09_24 : in STD_LOGIC_VECTOR(1 downto 0);
rxclk : in STD_LOGIC; --64 MHz clk from Radio Chip
IQenable : in std_logic;
Isample_o : out std_logic_vector(15 downto 0);
Qsample_o : out std_logic_vector(15 downto 0);
IQValid_o : out std_logic;
rx_bits_o : out std_logic_vector(1 downto 0);
rxclk_o : out std_logic
);
end at86rf215_rx_interface;
architecture Behavioral of at86rf215_rx_interface is
-- differential signals
signal rx_bits : std_logic_vector(1 downto 0) := "00";
signal rx_bits_d : std_logic_vector(1 downto 0) := "00";
--output data
signal I_Sample : std_logic_vector(13 downto 0) := (others=>'0');
signal Q_Sample : std_logic_vector(13 downto 0) := (others=>'0');
-- state variables
signal ibit_counter : std_logic_vector(3 downto 0) := x"0";
signal inc_icntr : std_logic := '0';
signal icntr_ovf : std_logic := '0';
signal qbit_counter : std_logic_vector(3 downto 0) := x"0";
signal inc_qcntr : std_logic := '0';
signal qcntr_ovf : std_logic := '0';
signal ien,qen : std_logic := '0';
constant I_SYNC : std_logic_vector := "10";
constant Q_SYNC : std_logic_vector := "01";
type state_type is (IDLE,ISAMPLE,QSAMPLE);
signal current_state, next_state : state_type := IDLE;
begin
-- debug IO's
rxclk_o <= rxclk;
rx_bits_o <= rx_bits_d;
-- RX FSM
Rx_state_transit : process(reset_n,rxclk)
begin
if(reset_n ='0') then
rx_bits_d <= "00";
current_state <= IDLE;
else
if(rising_edge(rxclk)) then
--rx_bits are swapped, as selectio output bits are somehow shifted
rx_bits_d <= rxd_09_24(0) & rxd_09_24(1);
current_state <= next_state;
end if;
end if;
end process;
Rx_Sampling_FSM : process(current_state,rx_bits_d,icntr_ovf,qcntr_ovf)
begin
inc_icntr <= '0';
inc_qcntr <= '0';
ien <= '0';
qen <= '0';
case current_State is
when IDLE =>
if (IQenable = '1') then
if(rx_bits_d = I_SYNC) then
next_state <= ISAMPLE;
else
next_state <= IDLE;
end if;
end if;
when ISAMPLE =>
if(icntr_ovf = '1') then
if(rx_bits_d = Q_SYNC) then
next_state <= QSAMPLE;
else
next_state <= IDLE;
end if;
else
inc_icntr <= '1';
ien <= '1';
next_state <= ISAMPLE;
end if;
when QSAMPLE =>
if(qcntr_ovf = '1') then
if(rx_bits_d = I_SYNC) then
next_state <= ISAMPLE;
else
next_state <= IDLE;
end if;
else
inc_qcntr <= '1';
qen <= '1';
next_state <= QSAMPLE;
end if;
when others =>
next_state <= IDLE;
end case;
end process;
cntr_proc: process(reset_n,rxclk)
begin
if(reset_n = '0') then
ibit_counter <= x"0";
icntr_ovf <= '0';
qbit_counter <= x"0";
qcntr_ovf <= '0';
else
if(rising_edge(rxclk)) then
if(ien = '1') then
I_Sample <= I_Sample(11 downto 0) & rx_bits_d;
end if;
if(qen = '1') then
Q_Sample <= Q_Sample(11 downto 0) & rx_bits_d;
end if;
if(inc_icntr = '1') then
if(ibit_counter < 6) then
ibit_counter <= ibit_counter + 1;
icntr_ovf <= '0';
else
ibit_counter <= X"0";
icntr_ovf <= '1';
end if;
else
icntr_ovf <= '0';
end if;
if(inc_qcntr = '1') then
if(qbit_counter < 6) then
qbit_counter <= qbit_counter + 1;
qcntr_ovf <= '0';
else
qbit_counter <= X"0";
qcntr_ovf <= '1';
end if;
else
qcntr_ovf <= '0';
end if;
end if;
end if;
end process;
IQ_sample_output_process: process(reset_n,rxclk)
begin
if(reset_n = '0') then
ISample_o <= (others => '0');
QSample_o <= (others => '0');
IQValid_o <= '0';
else
if(rising_edge(rxclk)) then
if(icntr_ovf = '1') then
ISample_o <= I_Sample(13) & I_Sample(13) & I_Sample(13 downto 0);
end if;
if(qcntr_ovf = '1') then
QSample_o <= Q_Sample(13) & Q_Sample(13) & Q_Sample(13 downto 0);
IQValid_o <= '1';
else
IQValid_o <= '0';
end if;
end if;
end if;
end process;
end Behavioral;

Plik diff jest za duży Load Diff

Plik binarny nie jest wyświetlany.

Plik diff jest za duży Load Diff

Wyświetl plik

@ -2,6 +2,7 @@
`include "sys_ctrl.v"
`include "io_ctrl.v"
`include "smi_ctrl.v"
`include "lvds_rx.v"
module top(
input i_glob_clock,
@ -204,10 +205,6 @@ module top(
.USER_SIGNAL_TO_GLOBAL_BUFFER (lvds_clock),
.GLOBAL_BUFFER_OUTPUT(lvds_clock_buf) );
// Testing - output the clock signal (positive and negative) to the PMOD
assign io_pmod[0] = lvds_clock_buf;
assign io_pmod[1] = ~lvds_clock_buf;
// Differential 2.4GHz I/Q DDR signal
SB_IO #(
.PIN_TYPE(6'b000000), // Input only, DDR mode (sample on both pos edge and
@ -218,8 +215,8 @@ module top(
.PACKAGE_PIN(i_iq_rx_24_n), // Attention: this is the 'n' input, thus the actual values
// will need to be negated (PCB layout constraint)
.INPUT_CLK (lvds_clock_buf), // The I/O sampling clock with DDR
.D_IN_0 ( io_pmod[2] ), // the 0 deg data output
.D_IN_1 ( io_pmod[3]) ); // the 180 deg data output
.D_IN_0 ( w_lvds_rx_24_d0 ), // the 0 deg data output
.D_IN_1 ( w_lvds_rx_24_d1 ) );// the 180 deg data output
// Differential 0.9GHz I/Q DDR signal
SB_IO #(
@ -229,7 +226,52 @@ module top(
) iq_rx_09 (
.PACKAGE_PIN(i_iq_rx_09_p),
.INPUT_CLK (lvds_clock_buf), // The I/O sampling clock with DDR
.D_IN_0 ( io_pmod[4] ), // the 0 deg data output
.D_IN_1 ( io_pmod[5]) ); // the 180 deg data output
.D_IN_0 ( w_lvds_rx_09_d0 ), // the 0 deg data output
.D_IN_1 ( w_lvds_rx_09_d1 ) );// the 180 deg data output
//=========================================================================
// LVDS RX SIGNAL FROM MODEM
//=========================================================================
wire w_lvds_rx_09_d0; // 0 degree
wire w_lvds_rx_09_d1; // 180 degree
wire w_lvds_rx_24_d0; // 0 degree
wire w_lvds_rx_24_d1; // 180 degree
wire w_rx_09_fifo_full;
wire w_rx_09_fifo_write_clk;
wire w_rx_09_fifo_push;
wire [31:0] w_rx_09_fifo_data;
wire w_rx_24_fifo_full;
wire w_rx_24_fifo_write_clk;
wire w_rx_24_fifo_push;
wire [31:0] w_rx_24_fifo_data;
lvds_rx lvds_rx_09_inst
(
.i_reset (r_reset),
.i_ddr_clk (lvds_clock_buf),
.i_ddr_data ({w_lvds_rx_09_d0, w_lvds_rx_09_d1}),
.i_fifo_full (w_rx_09_fifo_full),
.o_fifo_write_clk (w_rx_09_fifo_write_clk),
.o_fifo_push (w_rx_09_fifo_push),
.o_fifo_data (w_rx_09_fifo_data)
);
lvds_rx lvds_rx_24_inst
(
.i_reset (r_reset),
.i_ddr_clk (lvds_clock_buf),
.i_ddr_data ({w_lvds_rx_24_d0, w_lvds_rx_24_d1}),
.i_fifo_full (w_rx_24_fifo_full),
.o_fifo_write_clk (w_rx_24_fifo_write_clk),
.o_fifo_push (w_rx_24_fifo_push),
.o_fifo_data (w_rx_24_fifo_data)
);
// Testing - output the clock signal (positive and negative) to the PMOD
assign io_pmod[0] = lvds_clock_buf;
assign io_pmod[1] = w_rx_09_fifo_push;
assign io_pmod[2] = w_rx_24_fifo_push;
assign io_pmod[7:3] = w_rx_09_fifo_data[29:26];
endmodule // top

Wyświetl plik

@ -1,2 +1,2 @@
cd Software/CaribouLite/libcariboulite/build/
cd software/libcariboulite/build/

Wyświetl plik

@ -0,0 +1 @@
Raspberry Pi source files, see https://iosoft.blog for details

Wyświetl plik

@ -0,0 +1,471 @@
// Raspberry Pi ADC DMA tests; see https://iosoft.blog for details
//
// Copyright (c) 2020 Jeremy P Bentham
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//
// v0.01 JPB 9/6/20 Adapted from rpi_adc_ads7884 v0.11
// Modified MCP3008 functions to match
// v0.02 JPB 9/6/20 Corrected MCP3008 min & max frequencies
// v0.03 JPB 10/6/20 Changed MCP3008 max frequency from 2 to 2.6 MHz
// v0.04 JPB 11/6/20 Moved CLOCK_HZ definition to top of rpi_dma_utils.h
#include <stdint.h>
#include <stdlib.h>
#include <unistd.h>
#include <stdio.h>
#include <signal.h>
#include <string.h>
#include <ctype.h>
#include "rpi_dma_utils.h"
#define VERSION "0.04"
#define MCP3008 // ADC to use: MCP3008 or ADS7884
#define SAMPLE_RATE 10000 // Default sample rate (samples/sec)
#if defined(MCP3008)
#define RX_SAMPLE_SIZE 4 // Number of raw Rx bytes per sample
#define ADC_CHAN 0 // ADC channel number
#define ADC_9_BITS 0 // Set non-zero for 9-bit data
#define SPI_CSVAL 0 // Additional CS register settings
#define MIN_SPI_FREQ 10000 // Minimum SPI frequency
#define MAX_SPI_FREQ 2600000 // Maximum SPI frequency
#define VC_MEM_SIZE(ns) (PAGE_SIZE + ((ns)+4)*RX_SAMPLE_SIZE)
#define ADC_VOLTAGE(n) (((n) * 3.3) / 1024.0)
#elif defined(ADS7884)
#define RX_SAMPLE_SIZE 2 // Number of raw Rx bytes per sample
#define ADC_CHAN 0 // ADC channel number (ignored)
#define SPI_CSVAL 0 // Additional CS register settings
#define MIN_SPI_FREQ 1000 // Minimum SPI frequency
#define MAX_SPI_FREQ 42000000// Maximum SPI frequency
#define ADC_9_BITS 1 // Set non-0 for 9-bit data (0 for 8-bit)
#define VC_MEM_SIZE(ns) (PAGE_SIZE + ((ns)+4)*RX_SAMPLE_SIZE)
#define ADC_VOLTAGE(n) (((n) * 3.3) / 1024.0)
#endif
#define SPI0_CE_NUM 0
#define SPI0_CE0_PIN 8
#define SPI0_MISO_PIN 9
#define SPI0_MOSI_PIN 10
#define SPI0_SCLK_PIN 11
#define SPI0_BASE (PHYS_REG_BASE + 0x204000)
#define SPI_CS 0x00
#define SPI_FIFO 0x04
#define SPI_CLK 0x08
#define SPI_DLEN 0x0c
#define SPI_DC 0x14
#define SPI_FIFO_CLR (3 << 4)
#define SPI_TX_FIFO_CLR (1 << 4)
#define SPI_TFR_ACT (1 << 7)
#define SPI_DMA_EN (1 << 8)
#define SPI_AUTO_CS (1 << 11)
// SPI register strings
char *spi_regstrs[] = {"CS", "FIFO", "CLK", "DLEN", "LTOH", "DC", ""};
// Buffer for processed ADC samples
uint16_t *sample_buff;
// Virtual memory pointers to acceess GPIO, DMA & SPI from user space
extern MEM_MAP gpio_regs, dma_regs;
MEM_MAP vc_mem, spi_regs;
void terminate(int sig);
void map_devices(void);
void get_uncached_mem(MEM_MAP *mp, int size);
int adc_sample(int chan);
int adc_dma_sample_mcp3008(MEM_MAP *mp, int chan);
int adc_sample_ads7884(int chan);
int adc_dma_samples(MEM_MAP *mp, int chan, uint16_t *buff, int nsamp);
int adc_dma_samples_mcp3008(MEM_MAP *mp, int chan, uint16_t *buff, int nsamp);
int adc_dma_samples_ads7884(MEM_MAP *mp, int chan, uint16_t *buff, int nsamp);
void dma_test_spi(MEM_MAP *mp);
void dma_wait(int chan);
int mcp3008_tx_data(void *buff, int chan);
int mcp3008_rx_value(void *buff);
int init_spi(int hz);
void spi_clear(void);
void spi_cs(int set);
void spi_xfer(uint8_t *txd, uint8_t *rxd, int len);
void spi_disable(void);
void disp_spi(void);
// Main program
int main(int argc, char *argv[])
{
int args=0, sample_count=0, sample_rate=SAMPLE_RATE;
int f, spi_freq, val, i, n;
printf("SPI ADC test v" VERSION "\n");
while (argc > ++args) // Process command-line args
{
if (argv[args][0] == '-')
{
switch (toupper(argv[args][1]))
{
case 'N': // -N: number of samples
if (args>=argc-1 || !isdigit(argv[args+1][0]))
fprintf(stderr, "Error: no sample count\n");
else
sample_count = atoi(argv[++args]);
break;
case 'R': // -R: sample rate (samples/sec)
if (args>=argc-1 || !isdigit(argv[args+1][0]))
fprintf(stderr, "Error: no sample rate\n");
else
sample_rate = atoi(argv[++args]);
break;
}
}
}
map_devices();
map_uncached_mem(&vc_mem, VC_MEM_SIZE(sample_count));
signal(SIGINT, terminate);
spi_freq = sample_rate * RX_SAMPLE_SIZE*8;
if (spi_freq < MIN_SPI_FREQ)
fail("Invalid sample rate\n");
f = init_spi(spi_freq);
if (sample_count == 0)
{
printf("SPI frequency %u Hz, %u sample/s\n", f, f/(RX_SAMPLE_SIZE*8));
val = adc_sample(ADC_CHAN);
printf("ADC value %u = %4.3fV\n", val, val*3.3/1024.0);
}
else
{
if (!(sample_buff = malloc((sample_count+4) * 2)))
fail("Can't allocate sample buffer\n");
printf("%u samples at %u S/s\n", sample_count, f/(RX_SAMPLE_SIZE*8));
n = adc_dma_samples(&vc_mem, ADC_CHAN, sample_buff, sample_count);
for (i=0; i<n; i++)
printf("%4.3f\n", ADC_VOLTAGE(sample_buff[i]));
}
terminate(0);
}
// Catastrophic failure in initial setup
void fail(char *s)
{
printf(s);
terminate(0);
}
// Free memory segments and exit
void terminate(int sig)
{
printf("Closing\n");
spi_disable();
stop_dma(DMA_CHAN_A);
stop_dma(DMA_CHAN_B);
unmap_periph_mem(&vc_mem);
unmap_periph_mem(&spi_regs);
unmap_periph_mem(&dma_regs);
unmap_periph_mem(&gpio_regs);
if (sample_buff)
free(sample_buff);
exit(0);
}
// Map GPIO, DMA and SPI registers into virtual mem (user space)
// If any of these fail, program will be terminated
void map_devices(void)
{
map_periph(&gpio_regs, (void *)GPIO_BASE, PAGE_SIZE);
map_periph(&dma_regs, (void *)DMA_BASE, PAGE_SIZE);
map_periph(&spi_regs, (void *)SPI0_BASE, PAGE_SIZE);
}
// Get uncached memory
void get_uncached_mem(MEM_MAP *mp, int size)
{
if (!map_uncached_mem(mp, size))
fail("Error: can't allocate uncached memory\n");
}
// Fetch sample from ADC
int adc_sample(int chan)
{
#if defined(MCP3008)
return(adc_dma_sample_mcp3008(&vc_mem, chan));
#elif defined(ADS7884)
adc_sample_ads7884(chan);
return(adc_sample_ads7884(chan));
#endif
}
// Fetch single sample from MCP3008 ADC using DMA
int adc_dma_sample_mcp3008(MEM_MAP *mp, int chan)
{
DMA_CB *cbs=mp->virt;
uint32_t dlen, *txd=(uint32_t *)(cbs+2);
uint8_t *rxdata=(uint8_t *)(txd+0x10);
enable_dma(DMA_CHAN_A);
enable_dma(DMA_CHAN_B);
dlen = 4;
txd[0] = (dlen << 16) | SPI_TFR_ACT;
mcp3008_tx_data(&txd[1], chan);
cbs[0].ti = DMA_SRCE_DREQ | (DMA_SPI_RX_DREQ << 16) | DMA_WAIT_RESP | DMA_CB_DEST_INC;
cbs[0].tfr_len = dlen;
cbs[0].srce_ad = REG_BUS_ADDR(spi_regs, SPI_FIFO);
cbs[0].dest_ad = MEM_BUS_ADDR(mp, rxdata);
cbs[1].ti = DMA_DEST_DREQ | (DMA_SPI_TX_DREQ << 16) | DMA_WAIT_RESP | DMA_CB_SRCE_INC;
cbs[1].tfr_len = dlen + 4;
cbs[1].srce_ad = MEM_BUS_ADDR(mp, txd);
cbs[1].dest_ad = REG_BUS_ADDR(spi_regs, SPI_FIFO);
*REG32(spi_regs, SPI_DC) = (8 << 24) | (4 << 16) | (8 << 8) | 4;
*REG32(spi_regs, SPI_CS) = SPI_TFR_ACT | SPI_DMA_EN | SPI_AUTO_CS | SPI_FIFO_CLR | SPI_CSVAL;
*REG32(spi_regs, SPI_DLEN) = 0;
start_dma(mp, DMA_CHAN_A, &cbs[0], 0);
start_dma(mp, DMA_CHAN_B, &cbs[1], 0);
dma_wait(DMA_CHAN_A);
#if DEBUG
for (int i=0; i<dlen; i++)
printf("%02X ", rxdata[i]);
printf("\n");
#endif
return(mcp3008_rx_value(rxdata));
}
// Fetch last sample from ADS7884 (call twice for current value)
int adc_sample_ads7884(int chan)
{
uint8_t txdata[4]={0xff,0,0,0xff}, rxdata[4];
spi_clear();
spi_cs(1);
spi_xfer(txdata, rxdata, sizeof(txdata));
spi_cs(0);
return(((int)rxdata[1] << 4) | ((int)rxdata[2] >> 4));
}
// Fetch samples from ADC using DMA
int adc_dma_samples(MEM_MAP *mp, int chan, uint16_t *buff, int nsamp)
{
#if defined(MCP3008)
return(adc_dma_samples_mcp3008(mp, chan, buff, nsamp));
#elif defined(ADS7884)
return(adc_dma_samples_ads7884(mp, chan, buff, nsamp));
#endif
}
// Fetch samples from MCP3008 ADC using DMA
int adc_dma_samples_mcp3008(MEM_MAP *mp, int chan, uint16_t *buff, int nsamp)
{
DMA_CB *cbs=mp->virt;
uint32_t i, dlen, *txd=(uint32_t *)(cbs+4), *pindata=(uint32_t *)(txd+0x10);
uint8_t *rxdata=(uint8_t *)(txd+0x20);
gpio_out(SPI0_CE0_PIN, 1); // Get control of CE pin
gpio_mode(SPI0_CE0_PIN, GPIO_OUT);
enable_dma(DMA_CHAN_A); // Enable 2 DMA channels
enable_dma(DMA_CHAN_B);
mcp3008_tx_data(&txd[1], chan); // Create Tx data word
dlen = nsamp * 4; // One 4-byte word per sample
*pindata = 1 << SPI0_CE0_PIN; // Data to set/clear Chip Select pin
txd[0] = (dlen << 16) | SPI_TFR_ACT;// First Tx byte: SPI settings
// Control block 0: read data from SPI FIFO
cbs[0].ti = DMA_SRCE_DREQ | (DMA_SPI_RX_DREQ << 16) | DMA_WAIT_RESP | DMA_CB_DEST_INC;
cbs[0].tfr_len = dlen;
cbs[0].srce_ad = REG_BUS_ADDR(spi_regs, SPI_FIFO);
cbs[0].dest_ad = MEM_BUS_ADDR(mp, rxdata);
// Control block 1: CS high
cbs[1].srce_ad = cbs[2].srce_ad = MEM_BUS_ADDR(mp, pindata);
cbs[1].dest_ad = REG_BUS_ADDR(gpio_regs, GPIO_SET0);
cbs[1].tfr_len = cbs[2].tfr_len = cbs[3].tfr_len = 4;
cbs[1].ti = cbs[2].ti = DMA_DEST_DREQ | (DMA_SPI_TX_DREQ << 16) | DMA_WAIT_RESP | DMA_CB_SRCE_INC;
// Control block 2: CS low
cbs[2].dest_ad = REG_BUS_ADDR(gpio_regs, GPIO_CLR0);
// Control block 3: write data to Tx FIFO
cbs[3].ti = DMA_DEST_DREQ | (DMA_SPI_TX_DREQ << 16) | DMA_WAIT_RESP | DMA_CB_SRCE_INC;
cbs[3].srce_ad = MEM_BUS_ADDR(mp, &txd[1]);
cbs[3].dest_ad = REG_BUS_ADDR(spi_regs, SPI_FIFO);
// Link CB1, CB2 and CB3 in endless loop
cbs[1].next_cb = MEM_BUS_ADDR(mp, &cbs[2]);
cbs[2].next_cb = MEM_BUS_ADDR(mp, &cbs[3]);
cbs[3].next_cb = MEM_BUS_ADDR(mp, &cbs[1]);
// DMA request every 4 bytes, panic if 8 bytes
*REG32(spi_regs, SPI_DC) = (8 << 24) | (4 << 16) | (8 << 8) | 4;
// Clear SPI length register and Tx & Rx FIFOs, enable DMA
*REG32(spi_regs, SPI_DLEN) = 0;
*REG32(spi_regs, SPI_CS) = SPI_TFR_ACT | SPI_DMA_EN | SPI_AUTO_CS | SPI_FIFO_CLR | SPI_CSVAL;
// Send out first Tx bytes
*REG32(spi_regs, SPI_FIFO) = txd[0];
// Start DMA, wait until complete
start_dma(mp, DMA_CHAN_A, &cbs[0], 0);
start_dma(mp, DMA_CHAN_B, &cbs[3], DMA_PRIORITY(15));
dma_wait(DMA_CHAN_A);
// Relinquish control of CE pin
gpio_mode(SPI0_CE0_PIN, GPIO_ALT0);
#if DEBUG
for (i=0; i<dlen; i++)
printf("%02X ", rxdata[i]);
printf("\n");
#endif
// Convert 32-bit raw values to 16-bit data
for (i=0; i<nsamp; i++)
buff[i] = mcp3008_rx_value(&rxdata[i*4]);
return(nsamp);
}
// Fetch samples from ADS7884 ADC using DMA
int adc_dma_samples_ads7884(MEM_MAP *mp, int chan, uint16_t *buff, int nsamp)
{
DMA_CB *cbs=mp->virt;
uint32_t i, dlen, shift, *txd=(uint32_t *)(cbs+3);
uint8_t *rxdata=(uint8_t *)(txd+0x10);
enable_dma(DMA_CHAN_A); // Enable DMA channels
enable_dma(DMA_CHAN_B);
dlen = (nsamp+3) * 2; // 2 bytes/sample, plus 3 dummy samples
// Control block 0: store Rx data in buffer
cbs[0].ti = DMA_SRCE_DREQ | (DMA_SPI_RX_DREQ << 16) | DMA_WAIT_RESP | DMA_CB_DEST_INC;
cbs[0].tfr_len = dlen;
cbs[0].srce_ad = REG_BUS_ADDR(spi_regs, SPI_FIFO);
cbs[0].dest_ad = MEM_BUS_ADDR(mp, rxdata);
// Control block 1: continuously repeat last Tx word (pulse CS low)
cbs[1].srce_ad = MEM_BUS_ADDR(mp, &txd[2]);
cbs[1].dest_ad = REG_BUS_ADDR(spi_regs, SPI_FIFO);
cbs[1].tfr_len = 4;
cbs[1].ti = DMA_DEST_DREQ | (DMA_SPI_TX_DREQ << 16) | DMA_WAIT_RESP | DMA_CB_SRCE_INC;
cbs[1].next_cb = MEM_BUS_ADDR(mp, &cbs[1]);
// Control block 2: send first 2 Tx words, then switch to CB1 for the rest
cbs[2].srce_ad = MEM_BUS_ADDR(mp, &txd[0]);
cbs[2].dest_ad = REG_BUS_ADDR(spi_regs, SPI_FIFO);
cbs[2].tfr_len = 8;
cbs[2].ti = DMA_DEST_DREQ | (DMA_SPI_TX_DREQ << 16) | DMA_WAIT_RESP | DMA_CB_SRCE_INC;
cbs[2].next_cb = MEM_BUS_ADDR(mp, &cbs[1]);
// DMA request every 4 bytes, panic if 8 bytes
*REG32(spi_regs, SPI_DC) = (8 << 24) | (4 << 16) | (8 << 8) | 4;
// Clear SPI length register and Tx & Rx FIFOs, enable DMA
*REG32(spi_regs, SPI_DLEN) = 0;
*REG32(spi_regs, SPI_CS) = SPI_TFR_ACT | SPI_DMA_EN | SPI_AUTO_CS | SPI_FIFO_CLR | SPI_CSVAL;
// Data to be transmited: 32-bit words, MS bit of LS byte is sent first
txd[0] = (dlen << 16) | SPI_TFR_ACT;// SPI config: data len & TI setting
txd[1] = 0xffffffff; // Set CS high
txd[2] = 0x01000100; // Pulse CS low
// Enable DMA, wait until complete
start_dma(mp, DMA_CHAN_A, &cbs[0], 0);
start_dma(mp, DMA_CHAN_B, &cbs[2], 0);
dma_wait(DMA_CHAN_A);
#if DEBUG
for (i=0; i<dlen; i++)
printf("%02X ", rxdata[i]);
printf("\n");
#endif
// Check whether Rx data has 1 bit delay with respect to Tx
shift = rxdata[4] & 0x80 ? 3 : 4;
// Convert raw data to 16-bit unsigned values, ignoring first 3
for (i=0; i<nsamp; i++)
buff[i] = ((rxdata[i*2+6]<<8 | rxdata[i*2+7]) >> shift) & 0x3ff;
return(nsamp);
}
// Wait until DMA is complete
void dma_wait(int chan)
{
int n = 1000;
do {
usleep(100);
} while (dma_transfer_len(chan) && --n);
if (n == 0)
printf("DMA transfer timeout\n");
}
// Return Tx data for MCP3008
int mcp3008_tx_data(void *buff, int chan)
{
#if ADC_9_BITS
uint8_t txd[2]={0xc0|(chan<<3), 0x00};
#else
uint8_t txd[3]={0x01, 0x80|(chan<<4), 0x00};
#endif
memcpy(buff, txd, sizeof(txd));
return(sizeof(txd));
}
// Return value from ADC Rx data
int mcp3008_rx_value(void *buff)
{
uint8_t *rxd=buff;
#if ADC_9_BITS
return((((int)rxd[0] << 9) | ((int)rxd[1] << 1)) & 0x3ff);
#else
return(((int)(rxd[1]&3)<<8) | rxd[2]);
#endif
}
// Initialise SPI0, given desired clock freq; return actual value
int init_spi(int hz)
{
int f, div = (CLOCK_HZ / hz + 1) & ~1;
gpio_set(SPI0_CE0_PIN, GPIO_ALT0, GPIO_NOPULL);
gpio_set(SPI0_MISO_PIN, GPIO_ALT0, GPIO_PULLUP);
gpio_set(SPI0_MOSI_PIN, GPIO_ALT0, GPIO_NOPULL);
gpio_set(SPI0_SCLK_PIN, GPIO_ALT0, GPIO_NOPULL);
while (div==0 || (f = CLOCK_HZ/div) > MAX_SPI_FREQ)
div += 2;
*REG32(spi_regs, SPI_CS) = 0x30;
*REG32(spi_regs, SPI_CLK) = div;
return(f);
}
// Clear SPI FIFOs
void spi_clear(void)
{
*REG32(spi_regs, SPI_CS) = SPI_FIFO_CLR;
}
// Set / clear SPI chip select
void spi_cs(int set)
{
uint32_t csval = *REG32(spi_regs, SPI_CS);
*REG32(spi_regs, SPI_CS) = set ? csval | 0x80 : csval & ~0x80;
}
// Transfer SPI bytes
void spi_xfer(uint8_t *txd, uint8_t *rxd, int len)
{
while (len--)
{
*REG8(spi_regs, SPI_FIFO) = *txd++;
while((*REG32(spi_regs, SPI_CS) & (1<<17)) == 0) ;
*rxd++ = *REG32(spi_regs, SPI_FIFO);
}
}
// Disable SPI
void spi_disable(void)
{
*REG32(spi_regs, SPI_CS) = SPI_FIFO_CLR;
*REG32(spi_regs, SPI_CS) = 0;
}
// Display DMA registers
void disp_spi(void)
{
volatile uint32_t *p=REG32(spi_regs, SPI_CS);
int i=0;
while (spi_regstrs[i][0])
printf("%-4s %08X ", spi_regstrs[i++], *p++);
printf("\n");
}
// EOF

Wyświetl plik

@ -0,0 +1,551 @@
// DMA tests for the Raspberry Pi, see https://iosoft.blog for details
//
// Copyright (c) 2020 Jeremy P Bentham
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//
// v0.10 JPB 25/5/20
//
#include <stdint.h>
#include <stdlib.h>
#include <stdio.h>
#include <unistd.h>
#include <fcntl.h>
#include <signal.h>
#include <string.h>
#include <sys/ioctl.h>
#include <sys/mman.h>
// Location of peripheral registers in physical memory
//#define PHYS_REG_BASE 0x20000000 // Pi Zero or 1
#define PHYS_REG_BASE 0x3F000000 // Pi 2 or 3
//#define PHYS_REG_BASE 0xFE000000 // Pi 4
// Location of peripheral registers in bus memory
#define BUS_REG_BASE 0x7E000000
// If non-zero, print debug information
#define DEBUG 0
// Output pin to use for LED
//#define LED_PIN 47 // Pi Zero onboard LED
#define LED_PIN 21 // Offboard LED pin
// PWM clock frequency and range (FREQ/RANGE = LED flash freq)
#define PWM_FREQ 100000
#define PWM_RANGE 20000
// If non-zero, set PWM clock using VideoCore mailbox
#define USE_VC_CLOCK_SET 0
// Size of memory page
#define PAGE_SIZE 0x1000
// Round up to nearest page
#define PAGE_ROUNDUP(n) ((n)%PAGE_SIZE==0 ? (n) : ((n)+PAGE_SIZE)&~(PAGE_SIZE-1))
// Size of uncached memory for DMA control blocks and data
#define DMA_MEM_SIZE PAGE_SIZE
// GPIO definitions
#define GPIO_BASE (PHYS_REG_BASE + 0x200000)
#define GPIO_MODE0 0x00
#define GPIO_SET0 0x1c
#define GPIO_CLR0 0x28
#define GPIO_LEV0 0x34
#define VIRT_GPIO_REG(a) ((uint32_t *)((uint32_t)virt_gpio_regs + (a)))
#define BUS_GPIO_REG(a) (GPIO_BASE-PHYS_REG_BASE+BUS_REG_BASE+(uint32_t)(a))
#define GPIO_IN 0
#define GPIO_OUT 1
#define GPIO_ALT0 4
#define GPIO_ALT2 6
#define GPIO_ALT3 7
#define GPIO_ALT4 3
#define GPIO_ALT5 2
// Virtual memory pointers to acceess GPIO, DMA and PWM from user space
void *virt_gpio_regs, *virt_dma_regs, *virt_pwm_regs;
// VC mailbox file descriptor & handle, and bus memory pointer
int mbox_fd, dma_mem_h;
void *bus_dma_mem;
// Convert memory bus address to physical address (for mmap)
#define BUS_PHYS_ADDR(a) ((void *)((uint32_t)(a)&~0xC0000000))
// Videocore mailbox memory allocation flags, see:
// https://github.com/raspberrypi/firmware/wiki/Mailbox-property-interface
typedef enum {
MEM_FLAG_DISCARDABLE = 1<<0, // can be resized to 0 at any time. Use for cached data
MEM_FLAG_NORMAL = 0<<2, // normal allocating alias. Don't use from ARM
MEM_FLAG_DIRECT = 1<<2, // 0xC alias uncached
MEM_FLAG_COHERENT = 2<<2, // 0x8 alias. Non-allocating in L2 but coherent
MEM_FLAG_ZERO = 1<<4, // initialise buffer to all zeros
MEM_FLAG_NO_INIT = 1<<5, // don't initialise (default is initialise to all ones)
MEM_FLAG_HINT_PERMALOCK = 1<<6, // Likely to be locked for long periods of time
MEM_FLAG_L1_NONALLOCATING=(MEM_FLAG_DIRECT | MEM_FLAG_COHERENT) // Allocating in L2
} VC_ALLOC_FLAGS;
// VC flags for unchached DMA memory
#define DMA_MEM_FLAGS (MEM_FLAG_DIRECT|MEM_FLAG_ZERO)
// Mailbox command/response structure
typedef struct {
uint32_t len, // Overall length (bytes)
req, // Zero for request, 1<<31 for response
tag, // Command number
blen, // Buffer length (bytes)
dlen; // Data length (bytes)
uint32_t uints[32-5]; // Data (108 bytes maximum)
} VC_MSG __attribute__ ((aligned (16)));
// DMA register definitions
#define DMA_CHAN 5
#define DMA_PWM_DREQ 5
#define DMA_BASE (PHYS_REG_BASE + 0x007000)
#define DMA_CS (DMA_CHAN*0x100)
#define DMA_CONBLK_AD (DMA_CHAN*0x100 + 0x04)
#define DMA_TI (DMA_CHAN*0x100 + 0x08)
#define DMA_SRCE_AD (DMA_CHAN*0x100 + 0x0c)
#define DMA_DEST_AD (DMA_CHAN*0x100 + 0x10)
#define DMA_TXFR_LEN (DMA_CHAN*0x100 + 0x14)
#define DMA_STRIDE (DMA_CHAN*0x100 + 0x18)
#define DMA_NEXTCONBK (DMA_CHAN*0x100 + 0x1c)
#define DMA_DEBUG (DMA_CHAN*0x100 + 0x20)
#define DMA_ENABLE 0xff0
#define VIRT_DMA_REG(a) ((volatile uint32_t *)((uint32_t)virt_dma_regs + a))
char *dma_regstrs[] = {"DMA CS", "CB_AD", "TI", "SRCE_AD", "DEST_AD",
"TFR_LEN", "STRIDE", "NEXT_CB", "DEBUG", ""};
// DMA control block (must be 32-byte aligned)
typedef struct {
uint32_t ti, // Transfer info
srce_ad, // Source address
dest_ad, // Destination address
tfr_len, // Transfer length
stride, // Transfer stride
next_cb, // Next control block
debug, // Debug register, zero in control block
unused;
} DMA_CB __attribute__ ((aligned(32)));
#define DMA_CB_DEST_INC (1<<4)
#define DMA_CB_SRC_INC (1<<8)
// Virtual memory for DMA descriptors and data buffers (uncached)
void *virt_dma_mem;
// Convert virtual DMA data address to a bus address
#define BUS_DMA_MEM(a) ((uint32_t)a-(uint32_t)virt_dma_mem+(uint32_t)bus_dma_mem)
// PWM controller
#define PWM_BASE (PHYS_REG_BASE + 0x20C000)
#define PWM_CTL 0x00 // Control
#define PWM_STA 0x04 // Status
#define PWM_DMAC 0x08 // DMA control
#define PWM_RNG1 0x10 // Channel 1 range
#define PWM_DAT1 0x14 // Channel 1 data
#define PWM_FIF1 0x18 // Channel 1 fifo
#define PWM_RNG2 0x20 // Channel 2 range
#define PWM_DAT2 0x24 // Channel 2 data
#define VIRT_PWM_REG(a) ((volatile uint32_t *)((uint32_t)virt_pwm_regs + (a)))
#define BUS_PWM_REG(a) (PWM_BASE-PHYS_REG_BASE+BUS_REG_BASE+(uint32_t)(a))
#define PWM_CTL_RPTL1 (1<<2) // Chan 1: repeat last data when FIFO empty
#define PWM_CTL_USEF1 (1<<5) // Chan 1: use FIFO
#define PWM_DMAC_ENAB (1<<31) // Start PWM DMA
#define PWM_ENAB 1 // Enable PWM
#define PWM_PIN 18 // GPIO pin for PWM output
#define PWM_OUT 1 // Set non-zero to enable PWM output pin
// Clock
void *virt_clk_regs;
#define CLK_BASE (PHYS_REG_BASE + 0x101000)
#define CLK_PWM_CTL 0xa0
#define CLK_PWM_DIV 0xa4
#define VIRT_CLK_REG(a) ((volatile uint32_t *)((uint32_t)virt_clk_regs + (a)))
#define CLK_PASSWD 0x5a000000
#define CLOCK_KHZ 250000
#define PWM_CLOCK_ID 0xa
#define FAIL(x) {printf(x); terminate(0);}
int dma_test_mem_transfer(void);
void dma_test_led_flash(int pin);
void dma_test_pwm_trigger(int pin);
void terminate(int sig);
void gpio_mode(int pin, int mode);
void gpio_out(int pin, int val);
uint8_t gpio_in(int pin);
int open_mbox(void);
void close_mbox(int fd);
uint32_t msg_mbox(int fd, VC_MSG *msgp);
void *map_segment(void *addr, int size);
void unmap_segment(void *addr, int size);
uint32_t alloc_vc_mem(int fd, uint32_t size, VC_ALLOC_FLAGS flags);
void *lock_vc_mem(int fd, int h);
uint32_t unlock_vc_mem(int fd, int h);
uint32_t free_vc_mem(int fd, int h);
uint32_t set_vc_clock(int fd, int id, uint32_t freq);
void disp_vc_msg(VC_MSG *msgp);
void enable_dma(void);
void start_dma(DMA_CB *cbp);
void stop_dma(void);
void disp_dma(void);
void init_pwm(int freq);
void start_pwm(void);
void stop_pwm(void);
// Main program
int main(int argc, char *argv[])
{
// Ensure cleanup if user hits ctrl-C
signal(SIGINT, terminate);
// Map GPIO, DMA and PWM registers into virtual mem (user space)
virt_gpio_regs = map_segment((void *)GPIO_BASE, PAGE_SIZE);
virt_dma_regs = map_segment((void *)DMA_BASE, PAGE_SIZE);
virt_pwm_regs = map_segment((void *)PWM_BASE, PAGE_SIZE);
virt_clk_regs = map_segment((void *)CLK_BASE, PAGE_SIZE);
enable_dma();
// Set LED pin as output, and set high
gpio_mode(LED_PIN, GPIO_OUT);
gpio_out(LED_PIN, 1);
// Use mailbox to get uncached memory for DMA decriptors and buffers
mbox_fd = open_mbox();
if ((dma_mem_h = alloc_vc_mem(mbox_fd, DMA_MEM_SIZE, DMA_MEM_FLAGS)) <= 0 ||
(bus_dma_mem = lock_vc_mem(mbox_fd, dma_mem_h)) == 0 ||
(virt_dma_mem = map_segment(BUS_PHYS_ADDR(bus_dma_mem), DMA_MEM_SIZE)) == 0)
FAIL("Error: can't allocate uncached memory\n");
printf("VC mem handle %u, phys %p, virt %p\n", dma_mem_h, bus_dma_mem, virt_dma_mem);
// Run DMA tests
dma_test_mem_transfer();
dma_test_led_flash(LED_PIN);
dma_test_pwm_trigger(LED_PIN);
terminate(0);
}
// DMA memory-to-memory test
int dma_test_mem_transfer(void)
{
DMA_CB *cbp = virt_dma_mem;
char *srce = (char *)(cbp+1);
char *dest = srce + 0x100;
strcpy(srce, "memory transfer OK");
memset(cbp, 0, sizeof(DMA_CB));
cbp->ti = DMA_CB_SRC_INC | DMA_CB_DEST_INC;
cbp->srce_ad = BUS_DMA_MEM(srce);
cbp->dest_ad = BUS_DMA_MEM(dest);
cbp->tfr_len = strlen(srce) + 1;
start_dma(cbp);
usleep(10);
#if DEBUG
disp_dma();
#endif
printf("DMA test: %s\n", dest[0] ? dest : "failed");
return(dest[0] != 0);
}
// DMA memory-to-GPIO test: flash LED
void dma_test_led_flash(int pin)
{
DMA_CB *cbp=virt_dma_mem;
uint32_t *data = (uint32_t *)(cbp+1), n;
printf("DMA test: flashing LED on GPIO pin %u\n", pin);
memset(cbp, 0, sizeof(DMA_CB));
*data = 1 << pin;
cbp->tfr_len = 4;
cbp->srce_ad = BUS_DMA_MEM(data);
for (n=0; n<16; n++)
{
usleep(200000);
cbp->dest_ad = BUS_GPIO_REG(n&1 ? GPIO_CLR0 : GPIO_SET0);
start_dma(cbp);
}
}
// DMA trigger test: fLash LED using PWM trigger
void dma_test_pwm_trigger(int pin)
{
DMA_CB *cbs=virt_dma_mem;
uint32_t n, *pindata=(uint32_t *)(cbs+4), *pwmdata=pindata+1;
printf("DMA test: PWM trigger, ctrl-C to exit\n");
memset(cbs, 0, sizeof(DMA_CB)*4);
// Transfers are triggered by PWM request
cbs[0].ti = cbs[1].ti = cbs[2].ti = cbs[3].ti = (1 << 6) | (DMA_PWM_DREQ << 16);
// Control block 0 and 2: clear & set LED pin, 4-byte transfer
cbs[0].srce_ad = cbs[2].srce_ad = BUS_DMA_MEM(pindata);
cbs[0].dest_ad = BUS_GPIO_REG(GPIO_CLR0);
cbs[2].dest_ad = BUS_GPIO_REG(GPIO_SET0);
cbs[0].tfr_len = cbs[2].tfr_len = 4;
*pindata = 1 << pin;
// Control block 1 and 3: update PWM FIFO (to clear DMA request)
cbs[1].srce_ad = cbs[3].srce_ad = BUS_DMA_MEM(pwmdata);
cbs[1].dest_ad = cbs[3].dest_ad = BUS_PWM_REG(PWM_FIF1);
cbs[1].tfr_len = cbs[3].tfr_len = 4;
*pwmdata = PWM_RANGE / 2;
// Link control blocks 0 to 3 in endless loop
for (n=0; n<4; n++)
cbs[n].next_cb = BUS_DMA_MEM(&cbs[(n+1)%4]);
// Enable PWM with data threshold 1, and DMA
init_pwm(PWM_FREQ);
*VIRT_PWM_REG(PWM_DMAC) = PWM_DMAC_ENAB|1;
start_pwm();
start_dma(&cbs[0]);
// Nothing to do while LED is flashing
sleep(4);
}
// Free memory segments and exit
void terminate(int sig)
{
printf("Closing\n");
stop_pwm();
stop_dma();
unmap_segment(virt_dma_mem, DMA_MEM_SIZE);
unlock_vc_mem(mbox_fd, dma_mem_h);
free_vc_mem(mbox_fd, dma_mem_h);
close_mbox(mbox_fd);
unmap_segment(virt_clk_regs, PAGE_SIZE);
unmap_segment(virt_pwm_regs, PAGE_SIZE);
unmap_segment(virt_dma_regs, PAGE_SIZE);
unmap_segment(virt_gpio_regs, PAGE_SIZE);
exit(0);
}
// ----- GPIO -----
// Set input or output
void gpio_mode(int pin, int mode)
{
uint32_t *reg = VIRT_GPIO_REG(GPIO_MODE0) + pin / 10, shift = (pin % 10) * 3;
*reg = (*reg & ~(7 << shift)) | (mode << shift);
}
// Set an O/P pin
void gpio_out(int pin, int val)
{
uint32_t *reg = VIRT_GPIO_REG(val ? GPIO_SET0 : GPIO_CLR0) + pin/32;
*reg = 1 << (pin % 32);
}
// Get an I/P pin value
uint8_t gpio_in(int pin)
{
uint32_t *reg = VIRT_GPIO_REG(GPIO_LEV0) + pin/32;
return (((*reg) >> (pin % 32)) & 1);
}
// ----- VIDEOCORE MAILBOX -----
// Open mailbox interface, return file descriptor
int open_mbox(void)
{
int fd;
if ((fd = open("/dev/vcio", 0)) < 0)
FAIL("Error: can't open VC mailbox\n");
return(fd);
}
// Close mailbox interface
void close_mbox(int fd)
{
if (fd >= 0)
close(fd);
}
// Send message to mailbox, return first response int, 0 if error
uint32_t msg_mbox(int fd, VC_MSG *msgp)
{
uint32_t ret=0, i;
for (i=msgp->dlen/4; i<=msgp->blen/4; i+=4)
msgp->uints[i++] = 0;
msgp->len = (msgp->blen + 6) * 4;
msgp->req = 0;
if (ioctl(fd, _IOWR(100, 0, void *), msgp) < 0)
printf("VC IOCTL failed\n");
else if ((msgp->req&0x80000000) == 0)
printf("VC IOCTL error\n");
else if (msgp->req == 0x80000001)
printf("VC IOCTL partial error\n");
else
ret = msgp->uints[0];
#if DEBUG
disp_vc_msg(msgp);
#endif
return(ret);
}
// Allocate memory on PAGE_SIZE boundary, return handle
uint32_t alloc_vc_mem(int fd, uint32_t size, VC_ALLOC_FLAGS flags)
{
VC_MSG msg={.tag=0x3000c, .blen=12, .dlen=12,
.uints={PAGE_ROUNDUP(size), PAGE_SIZE, flags}};
return(msg_mbox(fd, &msg));
}
// Lock allocated memory, return bus address
void *lock_vc_mem(int fd, int h)
{
VC_MSG msg={.tag=0x3000d, .blen=4, .dlen=4, .uints={h}};
return(h ? (void *)msg_mbox(fd, &msg) : 0);
}
// Unlock allocated memory
uint32_t unlock_vc_mem(int fd, int h)
{
VC_MSG msg={.tag=0x3000e, .blen=4, .dlen=4, .uints={h}};
return(h ? msg_mbox(fd, &msg) : 0);
}
// Free memory
uint32_t free_vc_mem(int fd, int h)
{
VC_MSG msg={.tag=0x3000f, .blen=4, .dlen=4, .uints={h}};
return(h ? msg_mbox(fd, &msg) : 0);
}
uint32_t set_vc_clock(int fd, int id, uint32_t freq)
{
VC_MSG msg1={.tag=0x38001, .blen=8, .dlen=8, .uints={id, 1}};
VC_MSG msg2={.tag=0x38002, .blen=12, .dlen=12, .uints={id, freq, 0}};
msg_mbox(fd, &msg1);
disp_vc_msg(&msg1);
msg_mbox(fd, &msg2);
disp_vc_msg(&msg2);
return(0);
}
// Display mailbox message
void disp_vc_msg(VC_MSG *msgp)
{
int i;
printf("VC msg len=%X, req=%X, tag=%X, blen=%x, dlen=%x, data ",
msgp->len, msgp->req, msgp->tag, msgp->blen, msgp->dlen);
for (i=0; i<msgp->blen/4; i++)
printf("%08X ", msgp->uints[i]);
printf("\n");
}
// ----- VIRTUAL MEMORY -----
// Get virtual memory segment for peripheral regs or physical mem
void *map_segment(void *addr, int size)
{
int fd;
void *mem;
size = PAGE_ROUNDUP(size);
if ((fd = open ("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC)) < 0)
FAIL("Error: can't open /dev/mem, run using sudo\n");
mem = mmap(0, size, PROT_WRITE|PROT_READ, MAP_SHARED, fd, (uint32_t)addr);
close(fd);
#if DEBUG
printf("Map %p -> %p\n", (void *)addr, mem);
#endif
if (mem == MAP_FAILED)
FAIL("Error: can't map memory\n");
return(mem);
}
// Free mapped memory
void unmap_segment(void *mem, int size)
{
if (mem)
munmap(mem, PAGE_ROUNDUP(size));
}
// ----- DMA -----
// Enable and reset DMA
void enable_dma(void)
{
*VIRT_DMA_REG(DMA_ENABLE) |= (1 << DMA_CHAN);
*VIRT_DMA_REG(DMA_CS) = 1 << 31;
}
// Start DMA, given first control block
void start_dma(DMA_CB *cbp)
{
*VIRT_DMA_REG(DMA_CONBLK_AD) = BUS_DMA_MEM(cbp);
*VIRT_DMA_REG(DMA_CS) = 2; // Clear 'end' flag
*VIRT_DMA_REG(DMA_DEBUG) = 7; // Clear error bits
*VIRT_DMA_REG(DMA_CS) = 1; // Start DMA
}
// Halt current DMA operation by resetting controller
void stop_dma(void)
{
if (virt_dma_regs)
*VIRT_DMA_REG(DMA_CS) = 1 << 31;
}
// Display DMA registers
void disp_dma(void)
{
uint32_t *p=(uint32_t *)VIRT_DMA_REG(DMA_CS);
int i=0;
while (dma_regstrs[i][0])
{
printf("%-7s %08X ", dma_regstrs[i++], *p++);
if (i%5==0 || dma_regstrs[i][0]==0)
printf("\n");
}
}
// ----- PWM -----
// Initialise PWM
void init_pwm(int freq)
{
stop_pwm();
if (*VIRT_PWM_REG(PWM_STA) & 0x100)
{
printf("PWM bus error\n");
*VIRT_PWM_REG(PWM_STA) = 0x100;
}
#if USE_VC_CLOCK_SET
set_vc_clock(mbox_fd, PWM_CLOCK_ID, freq);
#else
int divi=(CLOCK_KHZ*1000) / freq;
*VIRT_CLK_REG(CLK_PWM_CTL) = CLK_PASSWD | (1 << 5);
while (*VIRT_CLK_REG(CLK_PWM_CTL) & (1 << 7)) ;
*VIRT_CLK_REG(CLK_PWM_DIV) = CLK_PASSWD | (divi << 12);
*VIRT_CLK_REG(CLK_PWM_CTL) = CLK_PASSWD | 6 | (1 << 4);
while ((*VIRT_CLK_REG(CLK_PWM_CTL) & (1 << 7)) == 0) ;
#endif
usleep(100);
*VIRT_PWM_REG(PWM_RNG1) = PWM_RANGE;
*VIRT_PWM_REG(PWM_FIF1) = PWM_RANGE/2;
#if PWM_OUT
gpio_mode(PWM_PIN, GPIO_ALT5);
#endif
}
// Start PWM operation
void start_pwm(void)
{
*VIRT_PWM_REG(PWM_CTL) = PWM_CTL_USEF1 | PWM_ENAB;
}
// Stop PWM operation
void stop_pwm(void)
{
if (virt_pwm_regs)
{
*VIRT_PWM_REG(PWM_CTL) = 0;
usleep(100);
}
}
// EOF

Wyświetl plik

@ -0,0 +1,346 @@
// Raspberry Pi DMA utilities; see https://iosoft.blog for details
//
// Copyright (c) 2020 Jeremy P Bentham
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//
#include <stdint.h>
#include <stdlib.h>
#include <stdio.h>
#include <unistd.h>
#include <fcntl.h>
#include <signal.h>
#include <string.h>
#include <sys/ioctl.h>
#include <sys/mman.h>
#include "rpi_dma_utils.h"
// If non-zero, print debug information
#define DEBUG 0
// If non-zero, enable PWM hardware output
#define PWM_OUT 0
char *dma_regstrs[] = {"DMA CS", "CB_AD", "TI", "SRCE_AD", "DEST_AD",
"TFR_LEN", "STRIDE", "NEXT_CB", "DEBUG", ""};
char *gpio_mode_strs[] = {GPIO_MODE_STRS};
// Virtual memory pointers to acceess GPIO, DMA and PWM from user space
MEM_MAP pwm_regs, gpio_regs, dma_regs, clk_regs;
// Use mmap to obtain virtual address, given physical
void *map_periph(MEM_MAP *mp, void *phys, int size)
{
mp->phys = phys;
mp->size = PAGE_ROUNDUP(size);
mp->bus = (void *)((uint32_t)phys - PHYS_REG_BASE + BUS_REG_BASE);
mp->virt = map_segment(phys, mp->size);
return(mp->virt);
}
// Allocate uncached memory, get bus & phys addresses
void *map_uncached_mem(MEM_MAP *mp, int size)
{
void *ret;
mp->size = PAGE_ROUNDUP(size);
mp->fd = open_mbox();
ret = (mp->h = alloc_vc_mem(mp->fd, mp->size, DMA_MEM_FLAGS)) > 0 &&
(mp->bus = lock_vc_mem(mp->fd, mp->h)) != 0 &&
(mp->virt = map_segment(BUS_PHYS_ADDR(mp->bus), mp->size)) != 0
? mp->virt : 0;
printf("VC mem handle %u, phys %p, virt %p\n", mp->h, mp->bus, mp->virt);
return(ret);
}
// Free mapped peripheral or memory
void unmap_periph_mem(MEM_MAP *mp)
{
if (mp)
{
if (mp->fd)
{
unmap_segment(mp->virt, mp->size);
unlock_vc_mem(mp->fd, mp->h);
free_vc_mem(mp->fd, mp->h);
close_mbox(mp->fd);
}
else
unmap_segment(mp->virt, mp->size);
}
}
// ----- GPIO -----
// Set input or output with pullups
void gpio_set(int pin, int mode, int pull)
{
gpio_mode(pin, mode);
gpio_pull(pin, pull);
}
// Set I/P pullup or pulldown
void gpio_pull(int pin, int pull)
{
volatile uint32_t *reg = REG32(gpio_regs, GPIO_GPPUDCLK0) + pin / 32;
*REG32(gpio_regs, GPIO_GPPUD) = pull;
usleep(2);
*reg = pin << (pin % 32);
usleep(2);
*REG32(gpio_regs, GPIO_GPPUD) = 0;
*reg = 0;
}
// Set input or output
void gpio_mode(int pin, int mode)
{
volatile uint32_t *reg = REG32(gpio_regs, GPIO_MODE0) + pin / 10, shift = (pin % 10) * 3;
*reg = (*reg & ~(7 << shift)) | (mode << shift);
}
// Set an O/P pin
void gpio_out(int pin, int val)
{
volatile uint32_t *reg = REG32(gpio_regs, val ? GPIO_SET0 : GPIO_CLR0) + pin/32;
*reg = 1 << (pin % 32);
}
// Get an I/P pin value
uint8_t gpio_in(int pin)
{
volatile uint32_t *reg = REG32(gpio_regs, GPIO_LEV0) + pin/32;
return (((*reg) >> (pin % 32)) & 1);
}
// Display the values in a GPIO mode register
void disp_mode_vals(uint32_t mode)
{
int i;
for (i=0; i<10; i++)
printf("%u:%-4s ", i, gpio_mode_strs[(mode>>(i*3)) & 7]);
printf("\n");
}
// ----- VIDEOCORE MAILBOX -----
// Open mailbox interface, return file descriptor
int open_mbox(void)
{
int fd;
if ((fd = open("/dev/vcio", 0)) < 0)
fail("Error: can't open VC mailbox\n");
return(fd);
}
// Close mailbox interface
void close_mbox(int fd)
{
if (fd >= 0)
close(fd);
}
// Send message to mailbox, return first response int, 0 if error
uint32_t msg_mbox(int fd, VC_MSG *msgp)
{
uint32_t ret=0, i;
for (i=msgp->dlen/4; i<=msgp->blen/4; i+=4)
msgp->uints[i++] = 0;
msgp->len = (msgp->blen + 6) * 4;
msgp->req = 0;
if (ioctl(fd, _IOWR(100, 0, void *), msgp) < 0)
printf("VC IOCTL failed\n");
else if ((msgp->req&0x80000000) == 0)
printf("VC IOCTL error\n");
else if (msgp->req == 0x80000001)
printf("VC IOCTL partial error\n");
else
ret = msgp->uints[0];
#if DEBUG
disp_vc_msg(msgp);
#endif
return(ret);
}
// Allocate memory on PAGE_SIZE boundary, return handle
uint32_t alloc_vc_mem(int fd, uint32_t size, VC_ALLOC_FLAGS flags)
{
VC_MSG msg={.tag=0x3000c, .blen=12, .dlen=12,
.uints={PAGE_ROUNDUP(size), PAGE_SIZE, flags}};
return(msg_mbox(fd, &msg));
}
// Lock allocated memory, return bus address
void *lock_vc_mem(int fd, int h)
{
VC_MSG msg={.tag=0x3000d, .blen=4, .dlen=4, .uints={h}};
return(h ? (void *)msg_mbox(fd, &msg) : 0);
}
// Unlock allocated memory
uint32_t unlock_vc_mem(int fd, int h)
{
VC_MSG msg={.tag=0x3000e, .blen=4, .dlen=4, .uints={h}};
return(h ? msg_mbox(fd, &msg) : 0);
}
// Free memory
uint32_t free_vc_mem(int fd, int h)
{
VC_MSG msg={.tag=0x3000f, .blen=4, .dlen=4, .uints={h}};
return(h ? msg_mbox(fd, &msg) : 0);
}
uint32_t set_vc_clock(int fd, int id, uint32_t freq)
{
VC_MSG msg1={.tag=0x38001, .blen=8, .dlen=8, .uints={id, 1}};
VC_MSG msg2={.tag=0x38002, .blen=12, .dlen=12, .uints={id, freq, 0}};
msg_mbox(fd, &msg1);
disp_vc_msg(&msg1);
msg_mbox(fd, &msg2);
disp_vc_msg(&msg2);
return(0);
}
// Display mailbox message
void disp_vc_msg(VC_MSG *msgp)
{
int i;
printf("VC msg len=%X, req=%X, tag=%X, blen=%x, dlen=%x, data ",
msgp->len, msgp->req, msgp->tag, msgp->blen, msgp->dlen);
for (i=0; i<msgp->blen/4; i++)
printf("%08X ", msgp->uints[i]);
printf("\n");
}
// ----- VIRTUAL MEMORY -----
// Get virtual memory segment for peripheral regs or physical mem
void *map_segment(void *addr, int size)
{
int fd;
void *mem;
size = PAGE_ROUNDUP(size);
if ((fd = open ("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC)) < 0)
fail("Error: can't open /dev/mem, run using sudo\n");
mem = mmap(0, size, PROT_WRITE|PROT_READ, MAP_SHARED, fd, (uint32_t)addr);
close(fd);
#if DEBUG
printf("Map %p -> %p\n", (void *)addr, mem);
#endif
if (mem == MAP_FAILED)
fail("Error: can't map memory\n");
return(mem);
}
// Free mapped memory
void unmap_segment(void *mem, int size)
{
if (mem)
munmap(mem, PAGE_ROUNDUP(size));
}
// ----- DMA -----
// Enable and reset DMA
void enable_dma(int chan)
{
*REG32(dma_regs, DMA_ENABLE) |= (1 << chan);
*REG32(dma_regs, DMA_REG(chan, DMA_CS)) = 1 << 31;
}
// Start DMA, given first control block
void start_dma(MEM_MAP *mp, int chan, DMA_CB *cbp, uint32_t csval)
{
*REG32(dma_regs, DMA_REG(chan, DMA_CONBLK_AD)) = MEM_BUS_ADDR(mp, cbp);
*REG32(dma_regs, DMA_REG(chan, DMA_CS)) = 2; // Clear 'end' flag
*REG32(dma_regs, DMA_REG(chan, DMA_DEBUG)) = 7; // Clear error bits
*REG32(dma_regs, DMA_REG(chan, DMA_CS)) = 1|csval; // Start DMA
}
// Return remaining transfer length
uint32_t dma_transfer_len(int chan)
{
return(*REG32(dma_regs, DMA_REG(chan, DMA_TXFR_LEN)));
}
// Check if DMA is active
uint32_t dma_active(int chan)
{
return((*REG32(dma_regs, DMA_REG(chan, DMA_CS))) & 1);
}
// Halt current DMA operation by resetting controller
void stop_dma(int chan)
{
if (dma_regs.virt)
*REG32(dma_regs, DMA_REG(chan, DMA_CS)) = 1 << 31;
}
// Display DMA registers
void disp_dma(int chan)
{
volatile uint32_t *p=REG32(dma_regs, DMA_REG(chan, DMA_CS));
int i=0;
while (dma_regstrs[i][0])
{
printf("%-7s %08X ", dma_regstrs[i++], *p++);
if (i%5==0 || dma_regstrs[i][0]==0)
printf("\n");
}
}
// ----- PWM -----
// Initialise PWM
void init_pwm(int freq, int range, int val)
{
stop_pwm();
if (*REG32(pwm_regs, PWM_STA) & 0x100)
{
printf("PWM bus error\n");
*REG32(pwm_regs, PWM_STA) = 0x100;
}
#if USE_VC_CLOCK_SET
set_vc_clock(mbox_fd, PWM_CLOCK_ID, freq);
#else
int divi=CLOCK_HZ / freq;
*REG32(clk_regs, CLK_PWM_CTL) = CLK_PASSWD | (1 << 5);
while (*REG32(clk_regs, CLK_PWM_CTL) & (1 << 7)) ;
*REG32(clk_regs, CLK_PWM_DIV) = CLK_PASSWD | (divi << 12);
*REG32(clk_regs, CLK_PWM_CTL) = CLK_PASSWD | 6 | (1 << 4);
while ((*REG32(clk_regs, CLK_PWM_CTL) & (1 << 7)) == 0) ;
#endif
usleep(100);
*REG32(pwm_regs, PWM_RNG1) = range;
*REG32(pwm_regs, PWM_FIF1) = val;
#if PWM_OUT
gpio_mode(PWM_PIN, PWM_PIN==12 ? GPIO_ALT0 : GPIO_ALT5);
#endif
}
// Start PWM operation
void start_pwm(void)
{
*REG32(pwm_regs, PWM_CTL) = PWM_CTL_USEF1 | PWM_ENAB;
}
// Stop PWM operation
void stop_pwm(void)
{
if (pwm_regs.virt)
{
*REG32(pwm_regs, PWM_CTL) = 0;
usleep(100);
}
}
// EOF

Wyświetl plik

@ -0,0 +1,202 @@
// Raspberry Pi DMA utility definitions; see https://iosoft.blog for details
//
// Copyright (c) 2020 Jeremy P Bentham
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//
// Location of peripheral registers in physical memory
#define PHYS_REG_BASE PI_01_REG_BASE
#define PI_01_REG_BASE 0x20000000 // Pi Zero or 1
#define PI_23_REG_BASE 0x3F000000 // Pi 2 or 3
#define PI_4_REG_BASE 0xFE000000 // Pi 4
//#define CLOCK_HZ 250000000 // Pi 2 - 4
#define CLOCK_HZ 400000000 // Pi Zero
// Location of peripheral registers in bus memory
#define BUS_REG_BASE 0x7E000000
// If non-zero, print debug information
#define DEBUG 0
// If non-zero, set PWM clock using VideoCore mailbox
#define USE_VC_CLOCK_SET 0
// Size of memory page
#define PAGE_SIZE 0x1000
// Round up to nearest page
#define PAGE_ROUNDUP(n) ((n)%PAGE_SIZE==0 ? (n) : ((n)+PAGE_SIZE)&~(PAGE_SIZE-1))
// Structure for mapped peripheral or memory
typedef struct {
int fd, // File descriptor
h, // Memory handle
size; // Memory size
void *bus, // Bus address
*virt, // Virtual address
*phys; // Physical address
} MEM_MAP;
// Get virtual 8 and 32-bit pointers to register
#define REG8(m, x) ((volatile uint8_t *) ((uint32_t)(m.virt)+(uint32_t)(x)))
#define REG32(m, x) ((volatile uint32_t *)((uint32_t)(m.virt)+(uint32_t)(x)))
// Get bus address of register
#define REG_BUS_ADDR(m, x) ((uint32_t)(m.bus) + (uint32_t)(x))
// Convert uncached memory virtual address to bus address
#define MEM_BUS_ADDR(mp, a) ((uint32_t)a-(uint32_t)mp->virt+(uint32_t)mp->bus)
// Convert bus address to physical address (for mmap)
#define BUS_PHYS_ADDR(a) ((void *)((uint32_t)(a)&~0xC0000000))
// GPIO register definitions
#define GPIO_BASE (PHYS_REG_BASE + 0x200000)
#define GPIO_MODE0 0x00
#define GPIO_SET0 0x1c
#define GPIO_CLR0 0x28
#define GPIO_LEV0 0x34
#define GPIO_GPPUD 0x94
#define GPIO_GPPUDCLK0 0x98
// GPIO I/O definitions
#define GPIO_IN 0
#define GPIO_OUT 1
#define GPIO_ALT0 4
#define GPIO_ALT1 5
#define GPIO_ALT2 6
#define GPIO_ALT3 7
#define GPIO_ALT4 3
#define GPIO_ALT5 2
#define GPIO_MODE_STRS "IN","OUT","ALT5","ALT4","ALT0","ALT1","ALT2","ALT3"
#define GPIO_NOPULL 0
#define GPIO_PULLDN 1
#define GPIO_PULLUP 2
// Videocore mailbox memory allocation flags, see:
// https://github.com/raspberrypi/firmware/wiki/Mailbox-property-interface
typedef enum {
MEM_FLAG_DISCARDABLE = 1<<0, // can be resized to 0 at any time. Use for cached data
MEM_FLAG_NORMAL = 0<<2, // normal allocating alias. Don't use from ARM
MEM_FLAG_DIRECT = 1<<2, // 0xC alias uncached
MEM_FLAG_COHERENT = 2<<2, // 0x8 alias. Non-allocating in L2 but coherent
MEM_FLAG_ZERO = 1<<4, // initialise buffer to all zeros
MEM_FLAG_NO_INIT = 1<<5, // don't initialise (default is initialise to all ones)
MEM_FLAG_HINT_PERMALOCK = 1<<6, // Likely to be locked for long periods of time
MEM_FLAG_L1_NONALLOCATING=(MEM_FLAG_DIRECT | MEM_FLAG_COHERENT) // Allocating in L2
} VC_ALLOC_FLAGS;
// VC flags for unchached DMA memory
#define DMA_MEM_FLAGS (MEM_FLAG_DIRECT|MEM_FLAG_ZERO)
// Mailbox command/response structure
typedef struct {
uint32_t len, // Overall length (bytes)
req, // Zero for request, 1<<31 for response
tag, // Command number
blen, // Buffer length (bytes)
dlen; // Data length (bytes)
uint32_t uints[32-5]; // Data (108 bytes maximum)
} VC_MSG __attribute__ ((aligned (16)));
// DMA channels and data requests
#define DMA_CHAN_A 10
#define DMA_CHAN_B 11
#define DMA_PWM_DREQ 5
#define DMA_SPI_TX_DREQ 6
#define DMA_SPI_RX_DREQ 7
#define DMA_BASE (PHYS_REG_BASE + 0x007000)
// DMA register addresses offset by 0x100 * chan_num
#define DMA_CS 0x00
#define DMA_CONBLK_AD 0x04
#define DMA_TI 0x08
#define DMA_SRCE_AD 0x0c
#define DMA_DEST_AD 0x10
#define DMA_TXFR_LEN 0x14
#define DMA_STRIDE 0x18
#define DMA_NEXTCONBK 0x1c
#define DMA_DEBUG 0x20
#define DMA_REG(ch, r) ((r)==DMA_ENABLE ? DMA_ENABLE : (ch)*0x100+(r))
#define DMA_ENABLE 0xff0
// DMA register values
#define DMA_WAIT_RESP (1 << 3)
#define DMA_CB_DEST_INC (1 << 4)
#define DMA_DEST_DREQ (1 << 6)
#define DMA_CB_SRCE_INC (1 << 8)
#define DMA_SRCE_DREQ (1 << 10)
#define DMA_PRIORITY(n) ((n) << 16)
// DMA control block (must be 32-byte aligned)
typedef struct {
uint32_t ti, // Transfer info
srce_ad, // Source address
dest_ad, // Destination address
tfr_len, // Transfer length
stride, // Transfer stride
next_cb, // Next control block
debug, // Debug register, zero in control block
unused;
} DMA_CB __attribute__ ((aligned(32)));
// PWM controller registers
#define PWM_BASE (PHYS_REG_BASE + 0x20C000)
#define PWM_CTL 0x00 // Control
#define PWM_STA 0x04 // Status
#define PWM_DMAC 0x08 // DMA control
#define PWM_RNG1 0x10 // Channel 1 range
#define PWM_DAT1 0x14 // Channel 1 data
#define PWM_FIF1 0x18 // Channel 1 fifo
#define PWM_RNG2 0x20 // Channel 2 range
#define PWM_DAT2 0x24 // Channel 2 data
// PWM register values
#define PWM_CTL_RPTL1 (1<<2) // Chan 1: repeat last data when FIFO empty
#define PWM_CTL_USEF1 (1<<5) // Chan 1: use FIFO
#define PWM_DMAC_ENAB (1<<31) // Start PWM DMA
#define PWM_ENAB 1 // Enable PWM
#define PWM_PIN 12 // GPIO pin for PWM output, 12 or 18
// Clock registers and values
#define CLK_BASE (PHYS_REG_BASE + 0x101000)
#define CLK_PWM_CTL 0xa0
#define CLK_PWM_DIV 0xa4
#define CLK_PASSWD 0x5a000000
#define PWM_CLOCK_ID 0xa
void fail(char *s);
void *map_periph(MEM_MAP *mp, void *phys, int size);
void *map_uncached_mem(MEM_MAP *mp, int size);
void unmap_periph_mem(MEM_MAP *mp);
void gpio_set(int pin, int mode, int pull);
void gpio_pull(int pin, int pull);
void gpio_mode(int pin, int mode);
void gpio_out(int pin, int val);
uint8_t gpio_in(int pin);
void disp_mode_vals(uint32_t mode);
int open_mbox(void);
void close_mbox(int fd);
uint32_t msg_mbox(int fd, VC_MSG *msgp);
void *map_segment(void *addr, int size);
void unmap_segment(void *addr, int size);
uint32_t alloc_vc_mem(int fd, uint32_t size, VC_ALLOC_FLAGS flags);
void *lock_vc_mem(int fd, int h);
uint32_t unlock_vc_mem(int fd, int h);
uint32_t free_vc_mem(int fd, int h);
uint32_t set_vc_clock(int fd, int id, uint32_t freq);
void disp_vc_msg(VC_MSG *msgp);
void enable_dma(int chan);
void start_dma(MEM_MAP *mp, int chan, DMA_CB *cbp, uint32_t csval);
uint32_t dma_transfer_len(int chan);
uint32_t dma_active(int chan);
void stop_dma(int chan);
void disp_dma(int chan);
void init_pwm(int freq, int range, int val);
void start_pwm(void);
void stop_pwm(void);
// EOF

Wyświetl plik

@ -0,0 +1,388 @@
// Raspberry Pi WS2812 LED driver using SMI
// For detailed description, see https://iosoft.blog
//
// Copyright (c) 2020 Jeremy P Bentham
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//
// v0.01 JPB 16/7/20 Adapted from rpi_smi_adc_test v0.06
// v0.02 JPB 15/9/20 Addded RGB to GRB conversion
// v0.03 JPB 15/9/20 Added red-green flashing
// v0.04 JPB 16/9/20 Added test mode
// v0.05 JPB 19/9/20 Changed test mode colours
// v0.06 JPB 20/9/20 Outlined command-line data input
// v0.07 JPB 25/9/20 Command-line data input if not in test mode
// v0.08 JPB 26/9/20 Changed from 4 to 3 pulses per LED bit
// Added 4-bit zero preamble
// Added raw Tx data test
// v0.09 JPB 27/9/20 Added 16-channel option
// v0.10 JPB 28/9/20 Corrected Pi Zero caching problem
// v0.11 JPB 29/9/20 Added enable_dma before transfer (in case still active)
// Corrected DMA nsamp value (was byte count)
#include <stdio.h>
#include <signal.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <ctype.h>
#include "rpi_dma_utils.h"
#include "rpi_smi_defs.h"
#if PHYS_REG_BASE==PI_4_REG_BASE // Timings for RPi v4 (1.5 GHz)
#define SMI_TIMING 10, 15, 30, 15 // 400 ns cycle time
#else // Timings for RPi v0-3 (1 GHz)
#define SMI_TIMING 10, 10, 20, 10 // 400 ns cycle time
#endif
#define TX_TEST 0 // If non-zero, use dummy Tx data
#define LED_D0_PIN 8 // GPIO pin for D0 output
#define LED_NCHANS 8 // Number of LED channels (8 or 16)
#define LED_NBITS 24 // Number of data bits per LED
#define LED_PREBITS 4 // Number of zero bits before LED data
#define LED_POSTBITS 4 // Number of zero bits after LED data
#define BIT_NPULSES 3 // Number of O/P pulses per LED bit
#define CHAN_MAXLEDS 50 // Maximum number of LEDs per channel
#define CHASE_MSEC 100 // Delay time for chaser light test
#define REQUEST_THRESH 2 // DMA request threshold
#define DMA_CHAN 10 // DMA channel to use
// Length of data for 1 row (1 LED on each channel)
#define LED_DLEN (LED_NBITS * BIT_NPULSES)
// Transmit data type, 8 or 16 bits
#if LED_NCHANS > 8
#define TXDATA_T uint16_t
#else
#define TXDATA_T uint8_t
#endif
// Structures for mapped I/O devices, and non-volatile memory
extern MEM_MAP gpio_regs, dma_regs;
MEM_MAP vc_mem, clk_regs, smi_regs;
// Pointers to SMI registers
volatile SMI_CS_REG *smi_cs;
volatile SMI_L_REG *smi_l;
volatile SMI_A_REG *smi_a;
volatile SMI_D_REG *smi_d;
volatile SMI_DMC_REG *smi_dmc;
volatile SMI_DSR_REG *smi_dsr;
volatile SMI_DSW_REG *smi_dsw;
volatile SMI_DCS_REG *smi_dcs;
volatile SMI_DCA_REG *smi_dca;
volatile SMI_DCD_REG *smi_dcd;
// Ofset into Tx data buffer, given LED number in chan
#define LED_TX_OSET(n) (LED_PREBITS + (LED_DLEN * (n)))
// Size of data buffers & NV memory, given number of LEDs per chan
#define TX_BUFF_LEN(n) (LED_TX_OSET(n) + LED_POSTBITS)
#define TX_BUFF_SIZE(n) (TX_BUFF_LEN(n) * sizeof(TXDATA_T))
#define VC_MEM_SIZE (PAGE_SIZE + TX_BUFF_SIZE(CHAN_MAXLEDS))
// RGB values for test mode (1 value for each of 16 channels)
int on_rgbs[16] = {0xff0000, 0x00ff00, 0x0000ff, 0xffffff,
0xff4040, 0x40ff40, 0x4040ff, 0x404040,
0xff0000, 0x00ff00, 0x0000ff, 0xffffff,
0xff4040, 0x40ff40, 0x4040ff, 0x404040};
int off_rgbs[16];
#if TX_TEST
// Data for simple transmission test
TXDATA_T tx_test_data[] = {1, 2, 3, 4, 5, 6, 7, 0};
#endif
TXDATA_T *txdata; // Pointer to uncached Tx data buffer
TXDATA_T tx_buffer[TX_BUFF_LEN(CHAN_MAXLEDS)]; // Tx buffer for assembling data
int testmode, chan_ledcount=1; // Command-line parameters
int rgb_data[CHAN_MAXLEDS][LED_NCHANS]; // RGB data
int chan_num; // Current channel for data I/P
void rgb_txdata(int *rgbs, TXDATA_T *txd);
int str_rgb(char *s, int rgbs[][LED_NCHANS], int chan);
void swap_bytes(void *data, int len);
int hexdig(char c);
void map_devices(void);
void fail(char *s);
void terminate(int sig);
void init_smi(int width, int ns, int setup, int hold, int strobe);
void setup_smi_dma(MEM_MAP *mp, int nsamp);
void start_smi(MEM_MAP *mp);
int main(int argc, char *argv[])
{
int args=0, n, oset=0;
while (argc > ++args) // Process command-line args
{
if (argv[args][0] == '-')
{
switch (toupper(argv[args][1]))
{
case 'N': // -N: number of LEDs per channel
if (args >= argc-1)
fprintf(stderr, "Error: no numeric value\n");
else
chan_ledcount = atoi(argv[++args]);
break;
case 'T': // -T: test mode
testmode = 1;
break;
default: // Otherwise error
printf("Unrecognised option '%c'\n", argv[args][1]);
printf("Options:\n"
" -n num number of LEDs per channel\n"\
" -t Test mode (flash LEDs)\n"\
);
return(1);
}
}
else if (chan_num<LED_NCHANS && hexdig(argv[args][0])>=0 &&
(n=str_rgb(argv[args], rgb_data, chan_num))>0)
{
chan_ledcount = n > chan_ledcount ? n : chan_ledcount;
chan_num++;
}
}
signal(SIGINT, terminate);
map_devices();
init_smi(LED_NCHANS>8 ? SMI_16_BITS : SMI_8_BITS, SMI_TIMING);
map_uncached_mem(&vc_mem, VC_MEM_SIZE);
#if TX_TEST
oset = oset;
setup_smi_dma(&vc_mem, sizeof(tx_test_data)/sizeof(TXDATA_T));
#if LED_NCHANS <= 8
swap_bytes(tx_test_data, sizeof(tx_test_data));
#endif
memcpy(txdata, tx_test_data, sizeof(tx_test_data));
start_smi(&vc_mem);
usleep(10);
while (dma_active(DMA_CHAN))
usleep(10);
#else
setup_smi_dma(&vc_mem, TX_BUFF_LEN(chan_ledcount));
printf("%s %u LED%s per channel, %u channels\n", testmode ? "Testing" : "Setting",
chan_ledcount, chan_ledcount==1 ? "" : "s", LED_NCHANS);
if (testmode)
{
while (1)
{
if (chan_ledcount < 2)
rgb_txdata(oset&1 ? off_rgbs : on_rgbs, tx_buffer);
else
{
for (n=0; n<chan_ledcount; n++)
{
rgb_txdata(n==oset%chan_ledcount ? on_rgbs : off_rgbs,
&tx_buffer[LED_TX_OSET(n)]);
}
}
oset++;
#if LED_NCHANS <= 8
swap_bytes(tx_buffer, TX_BUFF_SIZE(chan_ledcount));
#endif
memcpy(txdata, tx_buffer, TX_BUFF_SIZE(chan_ledcount));
start_smi(&vc_mem);
usleep(CHASE_MSEC * 1000);
}
}
else
{
for (n=0; n<chan_ledcount; n++)
rgb_txdata(rgb_data[n], &tx_buffer[LED_TX_OSET(n)]);
#if LED_NCHANS <= 8
swap_bytes(tx_buffer, TX_BUFF_SIZE(chan_ledcount));
#endif
memcpy(txdata, tx_buffer, TX_BUFF_SIZE(chan_ledcount));
enable_dma(DMA_CHAN);
start_smi(&vc_mem);
usleep(10);
while (dma_active(DMA_CHAN))
usleep(10);
}
#endif
terminate(0);
return(0);
}
// Convert RGB text string into integer data, for given channel
// Return number of data points for this channel
int str_rgb(char *s, int rgbs[][LED_NCHANS], int chan)
{
int i=0;
char *p;
while (chan<LED_NCHANS && i<CHAN_MAXLEDS && hexdig(*s)>=0)
{
rgbs[i++][chan] = strtoul(s, &p, 16);
s = *p ? p+1 : p;
}
return(i);
}
// Set Tx data for 8 or 16 chans, 1 LED per chan, given 1 RGB val per chan
// Logic 1 is 0.8us high, 0.4 us low, logic 0 is 0.4us high, 0.8us low
void rgb_txdata(int *rgbs, TXDATA_T *txd)
{
int i, n, msk;
// For each bit of the 24-bit RGB values..
for (n=0; n<LED_NBITS; n++)
{
// Mask to convert RGB to GRB, M.S bit first
msk = n==0 ? 0x8000 : n==8 ? 0x800000 : n==16 ? 0x80 : msk>>1;
// 1st byte or word is a high pulse on all lines
txd[0] = (TXDATA_T)0xffff;
// 2nd has high or low bits from data
// 3rd is a low pulse
txd[1] = txd[2] = 0;
for (i=0; i<LED_NCHANS; i++)
{
if (rgbs[i] & msk)
txd[1] |= (1 << i);
}
txd += BIT_NPULSES;
}
}
// Swap adjacent bytes in transmit data
void swap_bytes(void *data, int len)
{
uint16_t *wp = (uint16_t *)data;
len = (len + 1) / 2;
while (len-- > 0)
{
*wp = __builtin_bswap16(*wp);
wp++;
}
}
// Return hex digit value, -ve if not hex
int hexdig(char c)
{
c = toupper(c);
return((c>='0' && c<='9') ? c-'0' : (c>='A' && c<='F') ? c-'A'+10 : -1);
}
// Map GPIO, DMA and SMI registers into virtual mem (user space)
// If any of these fail, program will be terminated
void map_devices(void)
{
map_periph(&gpio_regs, (void *)GPIO_BASE, PAGE_SIZE);
map_periph(&dma_regs, (void *)DMA_BASE, PAGE_SIZE);
map_periph(&clk_regs, (void *)CLK_BASE, PAGE_SIZE);
map_periph(&smi_regs, (void *)SMI_BASE, PAGE_SIZE);
}
// Catastrophic failure in initial setup
void fail(char *s)
{
printf(s);
terminate(0);
}
// Free memory segments and exit
void terminate(int sig)
{
int i;
printf("Closing\n");
if (gpio_regs.virt)
{
for (i=0; i<LED_NCHANS; i++)
gpio_mode(LED_D0_PIN+i, GPIO_IN);
}
if (smi_regs.virt)
*REG32(smi_regs, SMI_CS) = 0;
stop_dma(DMA_CHAN);
unmap_periph_mem(&vc_mem);
unmap_periph_mem(&smi_regs);
unmap_periph_mem(&dma_regs);
unmap_periph_mem(&gpio_regs);
exit(0);
}
// Initialise SMI, given data width, time step, and setup/hold/strobe counts
// Step value is in nanoseconds: even numbers, 2 to 30
void init_smi(int width, int ns, int setup, int strobe, int hold)
{
int i, divi = ns / 2;
smi_cs = (SMI_CS_REG *) REG32(smi_regs, SMI_CS);
smi_l = (SMI_L_REG *) REG32(smi_regs, SMI_L);
smi_a = (SMI_A_REG *) REG32(smi_regs, SMI_A);
smi_d = (SMI_D_REG *) REG32(smi_regs, SMI_D);
smi_dmc = (SMI_DMC_REG *)REG32(smi_regs, SMI_DMC);
smi_dsr = (SMI_DSR_REG *)REG32(smi_regs, SMI_DSR0);
smi_dsw = (SMI_DSW_REG *)REG32(smi_regs, SMI_DSW0);
smi_dcs = (SMI_DCS_REG *)REG32(smi_regs, SMI_DCS);
smi_dca = (SMI_DCA_REG *)REG32(smi_regs, SMI_DCA);
smi_dcd = (SMI_DCD_REG *)REG32(smi_regs, SMI_DCD);
smi_cs->value = smi_l->value = smi_a->value = 0;
smi_dsr->value = smi_dsw->value = smi_dcs->value = smi_dca->value = 0;
if (*REG32(clk_regs, CLK_SMI_DIV) != divi << 12)
{
*REG32(clk_regs, CLK_SMI_CTL) = CLK_PASSWD | (1 << 5);
usleep(10);
while (*REG32(clk_regs, CLK_SMI_CTL) & (1 << 7)) ;
usleep(10);
*REG32(clk_regs, CLK_SMI_DIV) = CLK_PASSWD | (divi << 12);
usleep(10);
*REG32(clk_regs, CLK_SMI_CTL) = CLK_PASSWD | 6 | (1 << 4);
usleep(10);
while ((*REG32(clk_regs, CLK_SMI_CTL) & (1 << 7)) == 0) ;
usleep(100);
}
if (smi_cs->seterr)
smi_cs->seterr = 1;
smi_dsr->rsetup = smi_dsw->wsetup = setup;
smi_dsr->rstrobe = smi_dsw->wstrobe = strobe;
smi_dsr->rhold = smi_dsw->whold = hold;
smi_dmc->panicr = smi_dmc->panicw = 8;
smi_dmc->reqr = smi_dmc->reqw = REQUEST_THRESH;
smi_dsr->rwidth = smi_dsw->wwidth = width;
for (i=0; i<LED_NCHANS; i++)
gpio_mode(LED_D0_PIN+i, GPIO_ALT1);
}
// Set up SMI transfers using DMA
void setup_smi_dma(MEM_MAP *mp, int nsamp)
{
DMA_CB *cbs=mp->virt;
txdata = (TXDATA_T *)(cbs+1);
smi_dmc->dmaen = 1;
smi_cs->enable = 1;
smi_cs->clear = 1;
smi_cs->pxldat = 1;
smi_l->len = nsamp * sizeof(TXDATA_T);
smi_cs->write = 1;
enable_dma(DMA_CHAN);
cbs[0].ti = DMA_DEST_DREQ | (DMA_SMI_DREQ << 16) | DMA_CB_SRCE_INC | DMA_WAIT_RESP;
cbs[0].tfr_len = nsamp;
cbs[0].srce_ad = MEM_BUS_ADDR(mp, txdata);
cbs[0].dest_ad = REG_BUS_ADDR(smi_regs, SMI_D);
}
// Start SMI DMA transfers
void start_smi(MEM_MAP *mp)
{
DMA_CB *cbs=mp->virt;
start_dma(mp, DMA_CHAN, &cbs[0], 0);
smi_cs->start = 1;
}
// EOF

Wyświetl plik

@ -0,0 +1,384 @@
// Test of parallel AD9226 ADC using Raspberry Pi SMI (Secondary Memory Interface)
// For detailed description, see https://iosoft.blog
//
// Copyright (c) 2020 Jeremy P Bentham
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//
// v0.06 JPB 16/7/20 Tidied up for Github
#include <stdio.h>
#include <signal.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include "rpi_dma_utils.h"
#include "rpi_smi_defs.h"
// Set zero for single value, non-zero for block read
#define USE_DMA 1
// Use test pin in place of GPIO mode setting (to check timing)
#define USE_TEST_PIN 0
// SMI cycle timings
#define SMI_NUM_BITS SMI_16_BITS
#define SMI_TIMING SMI_TIMING_20M
#if PHYS_REG_BASE==PI_4_REG_BASE // Timings for RPi v4 (1.5 GHz)
#define SMI_TIMING_1M 10, 38, 74, 38 // 1 MS/s
#define SMI_TIMING_10M 6, 6, 13, 6 // 10 MS/s
#define SMI_TIMING_20M 4, 5, 9, 5 // 19.74 MS/s
#define SMI_TIMING_25M 4, 3, 8, 4 // 25 MS/s
#define SMI_TIMING_31M 4, 3, 6, 3 // 31.25 MS/s
#else // Timings for RPi v0-3 (1 GHz)
#define SMI_TIMING_1M 10, 25, 50, 25 // 1 MS/s
#define SMI_TIMING_10M 4, 6, 13, 6 // 10 MS/s
#define SMI_TIMING_20M 2, 6, 13, 6 // 20 MS/s
#define SMI_TIMING_25M 2, 5, 10, 5 // 25 MS/s
#define SMI_TIMING_31M 2, 4, 6, 4 // 31.25 MS/s
#define SMI_TIMING_42M 2, 3, 6, 3 // 41.66 MS/s
#define SMI_TIMING_50M 2, 3, 5, 2 // 50 MS/s
#endif
// Number of raw bytes per ADC sample
#define SAMPLE_SIZE 2
// Number of samples to be captured, and number to be discarded
#define NSAMPLES 500
#define PRE_SAMP 24
// Voltage calibration
#define ADC_ZERO 2080
#define ADC_SCALE 410.0
// GPIO pin numbers
#define ADC_D0_PIN 12
#define ADC_NPINS 12
#define SMI_SOE_PIN 6
#define SMI_SWE_PIN 7
#define SMI_DREQ_PIN 24
#define TEST_PIN 25
// DMA request threshold
#define REQUEST_THRESH 4
// SMI register names for diagnostic print
char *smi_regstrs[] = {
"CS","LEN","A","D","DSR0","DSW0","DSR1","DSW1",
"DSR2","DSW2","DSR3","DSW3","DMC","DCS","DCA","DCD",""
};
// SMI CS register field names for diagnostic print
#define STRS(x) STRS_(x) ","
#define STRS_(...) #__VA_ARGS__
char *smi_cs_regstrs = STRS(SMI_CS_FIELDS);
// Structures for mapped I/O devices, and non-volatile memory
extern MEM_MAP gpio_regs, dma_regs;
MEM_MAP vc_mem, clk_regs, smi_regs;
// Pointers to SMI registers
volatile SMI_CS_REG *smi_cs;
volatile SMI_L_REG *smi_l;
volatile SMI_A_REG *smi_a;
volatile SMI_D_REG *smi_d;
volatile SMI_DMC_REG *smi_dmc;
volatile SMI_DSR_REG *smi_dsr;
volatile SMI_DSW_REG *smi_dsw;
volatile SMI_DCS_REG *smi_dcs;
volatile SMI_DCA_REG *smi_dca;
volatile SMI_DCD_REG *smi_dcd;
// Buffer for captured samples
uint16_t sample_data[NSAMPLES];
// Non-volatile memory size
#define VC_MEM_SIZE(nsamp) (PAGE_SIZE + ((nsamp)+4)*SAMPLE_SIZE)
void map_devices(void);
void fail(char *s);
void terminate(int sig);
void smi_start(int nsamples, int packed);
uint32_t *adc_dma_start(MEM_MAP *mp, int nsamp);
int adc_dma_end(void *buff, uint16_t *data, int nsamp);
void init_smi(int width, int ns, int setup, int hold, int strobe);
void disp_smi(void);
void mode_word(uint32_t *wp, int n, uint32_t mode);
float val_volts(int val);
int adc_gpio_val(void);
void disp_reg_fields(char *regstrs, char *name, uint32_t val);
void dma_wait(int chan);
int main(int argc, char *argv[])
{
void *rxbuff;
int i;
signal(SIGINT, terminate);
map_devices();
for (i=0; i<ADC_NPINS; i++)
gpio_mode(ADC_D0_PIN+i, GPIO_IN);
gpio_mode(SMI_SOE_PIN, GPIO_ALT1);
#if !USE_DMA
init_smi(SMI_NUM_BITS, SMI_TIMING_1M);
while (1)
{
smi_start(PRE_SAMP, 1);
usleep(20);
int val = adc_gpio_val();
printf("%4u %1.3f\n", val, val_volts(val));
sleep(1);
}
#else
init_smi(SMI_NUM_BITS, SMI_TIMING);
#if USE_TEST_PIN
gpio_mode(TEST_PIN, GPIO_OUT);
gpio_out(TEST_PIN, 0);
#endif
map_uncached_mem(&vc_mem, VC_MEM_SIZE(NSAMPLES+PRE_SAMP));
smi_dmc->dmaen = 1;
smi_cs->enable = 1;
smi_cs->clear = 1;
rxbuff = adc_dma_start(&vc_mem, NSAMPLES);
smi_start(NSAMPLES, 1);
while (dma_active(DMA_CHAN_A)) ;
adc_dma_end(rxbuff, sample_data, NSAMPLES);
disp_reg_fields(smi_cs_regstrs, "CS", *REG32(smi_regs, SMI_CS));
smi_cs->enable = smi_dcs->enable = 0;
for (i=0; i<NSAMPLES; i++)
printf("%1.3f\n", val_volts(sample_data[i]));
#endif
terminate(0);
return(0);
}
// Map GPIO, DMA and SMI registers into virtual mem (user space)
// If any of these fail, program will be terminated
void map_devices(void)
{
map_periph(&gpio_regs, (void *)GPIO_BASE, PAGE_SIZE);
map_periph(&dma_regs, (void *)DMA_BASE, PAGE_SIZE);
map_periph(&clk_regs, (void *)CLK_BASE, PAGE_SIZE);
map_periph(&smi_regs, (void *)SMI_BASE, PAGE_SIZE);
}
// Catastrophic failure in initial setup
void fail(char *s)
{
printf(s);
terminate(0);
}
// Free memory segments and exit
void terminate(int sig)
{
int i;
printf("Closing\n");
if (gpio_regs.virt)
{
for (i=0; i<ADC_NPINS; i++)
gpio_mode(ADC_D0_PIN+i, GPIO_IN);
}
if (smi_regs.virt)
*REG32(smi_regs, SMI_CS) = 0;
stop_dma(DMA_CHAN_A);
unmap_periph_mem(&vc_mem);
unmap_periph_mem(&smi_regs);
unmap_periph_mem(&dma_regs);
unmap_periph_mem(&gpio_regs);
exit(0);
}
// Start SMI, given number of samples, optionally pack bytes into words
void smi_start(int nsamples, int packed)
{
smi_l->len = nsamples + PRE_SAMP;
smi_cs->pxldat = (packed != 0);
smi_cs->enable = 1;
smi_cs->clear = 1;
smi_cs->start = 1;
}
// Start DMA for SMI ADC, return Rx data buffer
uint32_t *adc_dma_start(MEM_MAP *mp, int nsamp)
{
DMA_CB *cbs=mp->virt;
uint32_t *data=(uint32_t *)(cbs+4), *pindata=data+8, *modes=data+0x10;
uint32_t *modep1=data+0x18, *modep2=modep1+1, *rxdata=data+0x20, i;
// Get current mode register values
for (i=0; i<3; i++)
modes[i] = modes[i+3] = *REG32(gpio_regs, GPIO_MODE0 + i*4);
// Get mode values with ADC pins set to SMI
for (i=ADC_D0_PIN; i<ADC_D0_PIN+ADC_NPINS; i++)
mode_word(&modes[i/10], i%10, GPIO_ALT1);
// Copy mode values into 32-bit words
*modep1 = modes[1];
*modep2 = modes[2];
*pindata = 1 << TEST_PIN;
enable_dma(DMA_CHAN_A);
// Control blocks 0 and 1: enable SMI I/P pins
cbs[0].ti = DMA_SRCE_DREQ | (DMA_SMI_DREQ << 16) | DMA_WAIT_RESP;
#if USE_TEST_PIN
cbs[0].tfr_len = 4;
cbs[0].srce_ad = MEM_BUS_ADDR(mp, pindata);
cbs[0].dest_ad = REG_BUS_ADDR(gpio_regs, GPIO_SET0);
cbs[0].next_cb = MEM_BUS_ADDR(mp, &cbs[2]);
#else
cbs[0].tfr_len = 4;
cbs[0].srce_ad = MEM_BUS_ADDR(mp, modep1);
cbs[0].dest_ad = REG_BUS_ADDR(gpio_regs, GPIO_MODE0+4);
cbs[0].next_cb = MEM_BUS_ADDR(mp, &cbs[1]);
#endif
cbs[1].tfr_len = 4;
cbs[1].srce_ad = MEM_BUS_ADDR(mp, modep2);
cbs[1].dest_ad = REG_BUS_ADDR(gpio_regs, GPIO_MODE0+8);
cbs[1].next_cb = MEM_BUS_ADDR(mp, &cbs[2]);
// Control block 2: read data
cbs[2].ti = DMA_SRCE_DREQ | (DMA_SMI_DREQ << 16) | DMA_CB_DEST_INC;
cbs[2].tfr_len = (nsamp + PRE_SAMP) * SAMPLE_SIZE;
cbs[2].srce_ad = REG_BUS_ADDR(smi_regs, SMI_D);
cbs[2].dest_ad = MEM_BUS_ADDR(mp, rxdata);
cbs[2].next_cb = MEM_BUS_ADDR(mp, &cbs[3]);
// Control block 3: disable SMI I/P pins
cbs[3].ti = DMA_CB_SRCE_INC | DMA_CB_DEST_INC;
#if USE_TEST_PIN
cbs[3].tfr_len = 4;
cbs[3].srce_ad = MEM_BUS_ADDR(mp, pindata);
cbs[3].dest_ad = REG_BUS_ADDR(gpio_regs, GPIO_CLR0);
#else
cbs[3].tfr_len = 3 * 4;
cbs[3].srce_ad = MEM_BUS_ADDR(mp, &modes[3]);
cbs[3].dest_ad = REG_BUS_ADDR(gpio_regs, GPIO_MODE0);
#endif
start_dma(mp, DMA_CHAN_A, &cbs[0], 0);
return(rxdata);
}
// ADC DMA is complete, get data
int adc_dma_end(void *buff, uint16_t *data, int nsamp)
{
uint16_t *bp = (uint16_t *)buff;
int i;
for (i=0; i<nsamp+PRE_SAMP; i++)
{
if (i >= PRE_SAMP)
*data++ = bp[i] >> 4;
}
return(nsamp);
}
// Initialise SMI, given data width, time step, and setup/hold/strobe counts
// Step value is in nanoseconds: even numbers, 2 to 30
void init_smi(int width, int ns, int setup, int strobe, int hold)
{
int divi = ns / 2;
smi_cs = (SMI_CS_REG *) REG32(smi_regs, SMI_CS);
smi_l = (SMI_L_REG *) REG32(smi_regs, SMI_L);
smi_a = (SMI_A_REG *) REG32(smi_regs, SMI_A);
smi_d = (SMI_D_REG *) REG32(smi_regs, SMI_D);
smi_dmc = (SMI_DMC_REG *)REG32(smi_regs, SMI_DMC);
smi_dsr = (SMI_DSR_REG *)REG32(smi_regs, SMI_DSR0);
smi_dsw = (SMI_DSW_REG *)REG32(smi_regs, SMI_DSW0);
smi_dcs = (SMI_DCS_REG *)REG32(smi_regs, SMI_DCS);
smi_dca = (SMI_DCA_REG *)REG32(smi_regs, SMI_DCA);
smi_dcd = (SMI_DCD_REG *)REG32(smi_regs, SMI_DCD);
smi_cs->value = smi_l->value = smi_a->value = 0;
smi_dsr->value = smi_dsw->value = smi_dcs->value = smi_dca->value = 0;
if (*REG32(clk_regs, CLK_SMI_DIV) != divi << 12)
{
*REG32(clk_regs, CLK_SMI_CTL) = CLK_PASSWD | (1 << 5);
usleep(10);
while (*REG32(clk_regs, CLK_SMI_CTL) & (1 << 7)) ;
usleep(10);
*REG32(clk_regs, CLK_SMI_DIV) = CLK_PASSWD | (divi << 12);
usleep(10);
*REG32(clk_regs, CLK_SMI_CTL) = CLK_PASSWD | 6 | (1 << 4);
usleep(10);
while ((*REG32(clk_regs, CLK_SMI_CTL) & (1 << 7)) == 0) ;
usleep(100);
}
if (smi_cs->seterr)
smi_cs->seterr = 1;
smi_dsr->rsetup = smi_dsw->wsetup = setup;
smi_dsr->rstrobe = smi_dsw->wstrobe = strobe;
smi_dsr->rhold = smi_dsw->whold = hold;
smi_dmc->panicr = smi_dmc->panicw = 8;
smi_dmc->reqr = smi_dmc->reqw = REQUEST_THRESH;
smi_dsr->rwidth = smi_dsw->wwidth = width;
}
// Display SMI registers
void disp_smi(void)
{
volatile uint32_t *p=REG32(smi_regs, SMI_CS);
int i=0;
while (smi_regstrs[i][0])
{
printf("%4s=%08X ", smi_regstrs[i++], *p++);
if (i%8==0 || smi_regstrs[i][0]==0)
printf("\n");
}
}
// Get GPIO mode value into 32-bit word
void mode_word(uint32_t *wp, int n, uint32_t mode)
{
uint32_t mask = 7 << (n * 3);
*wp = (*wp & ~mask) | (mode << (n * 3));
}
// Convert ADC value to voltage
float val_volts(int val)
{
return((ADC_ZERO - val) / ADC_SCALE);
}
// Return ADC value, using GPIO inputs
int adc_gpio_val(void)
{
int v = *REG32(gpio_regs, GPIO_LEV0);
return((v>>ADC_D0_PIN) & ((1 << ADC_NPINS)-1));
}
// Display bit values in register
void disp_reg_fields(char *regstrs, char *name, uint32_t val)
{
char *p=regstrs, *q, *r=regstrs;
uint32_t nbits, v;
printf("%s %08X", name, val);
while ((q = strchr(p, ':')) != 0)
{
p = q + 1;
nbits = 0;
while (*p>='0' && *p<='9')
nbits = nbits * 10 + *p++ - '0';
v = val & ((1 << nbits) - 1);
val >>= nbits;
if (v && *r!='_')
printf(" %.*s=%X", q-r, r, v);
while (*p==',' || *p==' ')
p = r = p + 1;
}
printf("\n");
}
// EOF

Wyświetl plik

@ -0,0 +1,359 @@
// Test of an R-2R DAC on the Raspberry Pi using SMI
// For detailed description, see https://iosoft.blog
//
// Copyright (c) 2020 Jeremy P Bentham
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//
// v0.01 JPB 16/7/20 Derived from rpi_smi_test v0.20
// Tidied up for github
#include <stdio.h>
#include <signal.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include "rpi_dma_utils.h"
#define USE_SMI 1
#define USE_DMA 1
#define DISP_ZEROS 0
#define SMI_A0_PIN 5
#define SMI_SOE_PIN 6
#define SMI_SWE_PIN 7
#define DAC_D0_PIN 8
#define DAC_NPINS 8
#define NSAMPLES 512
#define SMI_BASE (PHYS_REG_BASE + 0x600000)
#define SMI_CS 0x00 // Control & status
#define SMI_L 0x04 // Transfer length
#define SMI_A 0x08 // Address
#define SMI_D 0x0c // Data
#define SMI_DSR0 0x10 // Read settings device 0
#define SMI_DSW0 0x14 // Write settings device 0
#define SMI_DSR1 0x18 // Read settings device 1
#define SMI_DSW1 0x1c // Write settings device 1
#define SMI_DSR2 0x20 // Read settings device 2
#define SMI_DSW2 0x24 // Write settings device 2
#define SMI_DSR3 0x28 // Read settings device 3
#define SMI_DSW3 0x2c // Write settings device 3
#define SMI_DMC 0x30 // DMA control
#define SMI_DCS 0x34 // Direct control/status
#define SMI_DCA 0x38 // Direct address
#define SMI_DCD 0x3c // Direct data
#define SMI_FD 0x40 // FIFO debug
#define SMI_REGLEN (SMI_FD * 4)
#define SMI_DEV 0
#define SMI_8_BITS 0
#define SMI_16_BITS 1
#define SMI_18_BITS 2
#define SMI_9_BITS 3
#define DMA_SMI_DREQ 4
char *smi_regstrs[] = {
"CS","LEN","A","D","DSR0","DSW0","DSR1","DSW1",
"DSR2","DSW2","DSR3","DSW3","DMC","DCS","DCA","DCD",""
};
#define STRS(x) STRS_(x) ","
#define STRS_(...) #__VA_ARGS__
#define REG_DEF(name, fields) typedef union {struct {volatile uint32_t fields;}; volatile uint32_t value;} name
#define SMI_CS_FIELDS \
enable:1, done:1, active:1, start:1, clear:1, write:1, _x1:2,\
teen:1, intd:1, intt:1, intr:1, pvmode:1, seterr:1, pxldat:1, edreq:1,\
_x2:8, _x3:1, aferr:1, txw:1, rxr:1, txd:1, rxd:1, txe:1, rxf:1
REG_DEF(SMI_CS_REG, SMI_CS_FIELDS);
#define SMI_L_FIELDS \
len:32
REG_DEF(SMI_L_REG, SMI_L_FIELDS);
#define SMI_A_FIELDS \
addr:6, _x1:2, dev:2
REG_DEF(SMI_A_REG, SMI_A_FIELDS);
#define SMI_D_FIELDS \
data:32
REG_DEF(SMI_D_REG, SMI_D_FIELDS);
#define SMI_DMC_FIELDS \
reqw:6, reqr:6, panicw:6, panicr:6, dmap:1, _x1:3, dmaen:1
REG_DEF(SMI_DMC_REG, SMI_DMC_FIELDS);
#define SMI_DSR_FIELDS \
rstrobe:7, rdreq:1, rpace:7, rpaceall:1, rhold:6, fsetup:1, mode68:1, rsetup:6, rwidth:2
REG_DEF(SMI_DSR_REG, SMI_DSR_FIELDS);
#define SMI_DSW_FIELDS \
wstrobe:7, wdreq:1, wpace:7, wpaceall:1, whold:6, wswap:1, wformat:1, wsetup:6, wwidth:2
REG_DEF(SMI_DSW_REG, SMI_DSW_FIELDS);
#define SMI_DCS_FIELDS \
enable:1, start:1, done:1, write:1
REG_DEF(SMI_DCS_REG, SMI_DCS_FIELDS);
#define SMI_DCA_FIELDS \
addr:6, _x1:2, dev:2
REG_DEF(SMI_DCA_REG, SMI_DCA_FIELDS);
#define SMI_DCD_FIELDS \
data:32
REG_DEF(SMI_DCD_REG, SMI_DCD_FIELDS);
#define SMI_FLVL_FIELDS \
fcnt:6, _x1:2, flvl:6
REG_DEF(SMI_FLVL_REG, SMI_FLVL_FIELDS);
char *smi_cs_regstrs = STRS(SMI_CS_FIELDS);
#define CLK_SMI_CTL 0xb0
#define CLK_SMI_DIV 0xb4
extern MEM_MAP gpio_regs, dma_regs;
MEM_MAP vc_mem, clk_regs, smi_regs;
volatile SMI_CS_REG *smi_cs;
volatile SMI_L_REG *smi_l;
volatile SMI_A_REG *smi_a;
volatile SMI_D_REG *smi_d;
volatile SMI_DMC_REG *smi_dmc;
volatile SMI_DSR_REG *smi_dsr;
volatile SMI_DSW_REG *smi_dsw;
volatile SMI_DCS_REG *smi_dcs;
volatile SMI_DCA_REG *smi_dca;
volatile SMI_DCD_REG *smi_dcd;
#define TX_SAMPLE_SIZE 1 // Number of raw bytes per sample
#define VC_MEM_SIZE(ns) (PAGE_SIZE + ((ns)+4)*TX_SAMPLE_SIZE)
uint8_t sample_buff[NSAMPLES];
void dac_ladder_init(void);
void dac_ladder_write(int val);
void dac_ladder_dma(MEM_MAP *mp, uint8_t *data, int len, int repeat);
void map_devices(void);
void fail(char *s);
void terminate(int sig);
void init_smi(int width, int ns, int setup, int hold, int strobe);
void disp_smi(void);
void disp_reg_fields(char *regstrs, char *name, uint32_t val);
void dma_wait(int chan);
int main(int argc, char *argv[])
{
int i, sample_count=NSAMPLES;
signal(SIGINT, terminate);
map_devices();
init_smi(0, 1000, 25, 50, 25);
gpio_mode(SMI_SOE_PIN, GPIO_ALT1);
gpio_mode(SMI_SWE_PIN, GPIO_ALT1);
smi_cs->clear = 1;
dac_ladder_init();
for (i=0; i<sample_count; i++)
sample_buff[i] = (uint8_t)i;
#if !USE_DMA
while (1)
{
i = (i + 1) % sample_count;
dac_ladder_write(sample_buff[i]);
usleep(10);
}
#else
for (i=0; i<DAC_NPINS; i++)
gpio_mode(DAC_D0_PIN+i, GPIO_ALT1);
map_uncached_mem(&vc_mem, VC_MEM_SIZE(sample_count));
smi_dsr->rwidth = SMI_8_BITS;
smi_l->len = sample_count;
smi_dmc->dmaen = 1;
smi_cs->write = 1;
smi_cs->enable = 1;
smi_cs->clear = 1;
dac_ladder_dma(&vc_mem, sample_buff, sample_count, 0);
smi_cs->start = 1;
dma_wait(DMA_CHAN_A);
#endif
terminate(0);
return(0);
}
// Initialise resistor DAC
void dac_ladder_init(void)
{
int i;
#if USE_SMI
smi_cs->clear = smi_cs->seterr = smi_cs->aferr=1;
//smi_cs->enable = 1;
smi_dcs->enable = 1;
#endif
for (i=0; i<DAC_NPINS; i++)
gpio_mode(DAC_D0_PIN+i, USE_SMI ? GPIO_ALT1 : GPIO_OUT);
}
// Output value to resistor DAC
void dac_ladder_write(int val)
{
#if USE_SMI
smi_dcs->done = 1;
smi_dcs->write = 1;
smi_dcd->value = val & 0xff;
smi_dcs->start = 1;
#else
*REG32(gpio_regs, GPIO_SET0) = (val & 0xff) << DAC_D0_PIN;
*REG32(gpio_regs, GPIO_CLR0) = (~val & 0xff) << DAC_D0_PIN;
#endif
}
// DMA values to resistor DAC
void dac_ladder_dma(MEM_MAP *mp, uint8_t *data, int len, int repeat)
{
DMA_CB *cbs=mp->virt;
uint8_t *txdata=(uint8_t *)(cbs+1);
memcpy(txdata, data, len);
enable_dma(DMA_CHAN_A);
cbs[0].ti = DMA_DEST_DREQ | (DMA_SMI_DREQ << 16) | DMA_CB_SRCE_INC;
cbs[0].tfr_len = NSAMPLES;
cbs[0].srce_ad = MEM_BUS_ADDR(mp, txdata);
cbs[0].dest_ad = REG_BUS_ADDR(smi_regs, SMI_D);
cbs[0].next_cb = repeat ? MEM_BUS_ADDR(mp, &cbs[0]) : 0;
start_dma(mp, DMA_CHAN_A, &cbs[0], 0);
}
// Map GPIO, DMA and SMI registers into virtual mem (user space)
// If any of these fail, program will be terminated
void map_devices(void)
{
map_periph(&gpio_regs, (void *)GPIO_BASE, PAGE_SIZE);
map_periph(&dma_regs, (void *)DMA_BASE, PAGE_SIZE);
map_periph(&clk_regs, (void *)CLK_BASE, PAGE_SIZE);
map_periph(&smi_regs, (void *)SMI_BASE, PAGE_SIZE);
memset(smi_regs.virt, 0, SMI_REGLEN);
}
// Catastrophic failure in initial setup
void fail(char *s)
{
printf(s);
terminate(0);
}
// Free memory segments and exit
void terminate(int sig)
{
int i;
printf("Closing\n");
disp_reg_fields(smi_cs_regstrs, "CS", *REG32(smi_regs, SMI_CS));
for (i=0; i<DAC_NPINS; i++)
gpio_mode(DAC_D0_PIN+i, GPIO_IN);
if (smi_regs.virt)
*REG32(smi_regs, SMI_CS) = 0;
stop_dma(DMA_CHAN_A);
unmap_periph_mem(&vc_mem);
unmap_periph_mem(&smi_regs);
unmap_periph_mem(&dma_regs);
unmap_periph_mem(&gpio_regs);
exit(0);
}
// Initialise SMI, given data width, time step, and setup/hold/strobe counts
// Step value is in nanoseconds: even numbers, 2 to 30
void init_smi(int width, int ns, int setup, int strobe, int hold)
{
int divi = ns / 2;
smi_cs = (SMI_CS_REG *) REG32(smi_regs, SMI_CS);
smi_l = (SMI_L_REG *) REG32(smi_regs, SMI_L);
smi_a = (SMI_A_REG *) REG32(smi_regs, SMI_A);
smi_d = (SMI_D_REG *) REG32(smi_regs, SMI_D);
smi_dmc = (SMI_DMC_REG *)REG32(smi_regs, SMI_DMC);
smi_dsr = (SMI_DSR_REG *)REG32(smi_regs, SMI_DSR0);
smi_dsw = (SMI_DSW_REG *)REG32(smi_regs, SMI_DSW0);
smi_dcs = (SMI_DCS_REG *)REG32(smi_regs, SMI_DCS);
smi_dca = (SMI_DCA_REG *)REG32(smi_regs, SMI_DCA);
smi_dcd = (SMI_DCD_REG *)REG32(smi_regs, SMI_DCD);
smi_cs->value = smi_l->value = smi_a->value = 0;
smi_dsr->value = smi_dsw->value = smi_dcs->value = smi_dca->value = 0;
if (*REG32(clk_regs, CLK_SMI_DIV) != divi << 12)
{
*REG32(clk_regs, CLK_SMI_CTL) = CLK_PASSWD | (1 << 5);
usleep(10);
while (*REG32(clk_regs, CLK_SMI_CTL) & (1 << 7)) ;
usleep(10);
*REG32(clk_regs, CLK_SMI_DIV) = CLK_PASSWD | (divi << 12);
usleep(10);
*REG32(clk_regs, CLK_SMI_CTL) = CLK_PASSWD | 6 | (1 << 4);
usleep(10);
while ((*REG32(clk_regs, CLK_SMI_CTL) & (1 << 7)) == 0) ;
usleep(100);
}
if (smi_cs->seterr)
smi_cs->seterr = 1;
smi_dsr->rsetup = smi_dsw->wsetup = setup;
smi_dsr->rstrobe = smi_dsw->wstrobe = strobe;
smi_dsr->rhold = smi_dsw->whold = hold;
smi_dmc->panicr = smi_dmc->panicw = 8;
smi_dmc->reqr = smi_dmc->reqw = 2;
smi_dsr->rwidth = smi_dsw->wwidth = width;
}
// Display SMI registers
void disp_smi(void)
{
volatile uint32_t *p=REG32(smi_regs, SMI_CS);
int i=0;
while (smi_regstrs[i][0])
{
printf("%4s=%08X ", smi_regstrs[i++], *p++);
if (i%8==0 || smi_regstrs[i][0]==0)
printf("\n");
}
}
// Display bit values in register
void disp_reg_fields(char *regstrs, char *name, uint32_t val)
{
char *p=regstrs, *q, *r=regstrs;
uint32_t nbits, v;
printf("%s %08X", name, val);
while ((q = strchr(p, ':')) != 0)
{
p = q + 1;
nbits = 0;
while (*p>='0' && *p<='9')
nbits = nbits * 10 + *p++ - '0';
v = val & ((1 << nbits) - 1);
val >>= nbits;
if ((v || DISP_ZEROS) && *r!='_')
printf(" %.*s=%X", q-r, r, v);
while (*p==',' || *p==' ')
p = r = p + 1;
}
printf("\n");
}
// Wait until DMA is complete
void dma_wait(int chan)
{
int n = 1000;
do {
usleep(100);
} while (dma_transfer_len(chan) && --n);
if (n == 0)
printf("DMA transfer timeout\n");
}
// EOF

Wyświetl plik

@ -0,0 +1,100 @@
// Secondary Memory Interface definitions for Raspberry Pi
//
// v0.01 JPB 12/7/20 Adapted from rpi_smi_test v0.19
// Register definitions
#define SMI_BASE (PHYS_REG_BASE + 0x600000)
#define SMI_CS 0x00 // Control & status
#define SMI_L 0x04 // Transfer length
#define SMI_A 0x08 // Address
#define SMI_D 0x0c // Data
#define SMI_DSR0 0x10 // Read settings device 0
#define SMI_DSW0 0x14 // Write settings device 0
#define SMI_DSR1 0x18 // Read settings device 1
#define SMI_DSW1 0x1c // Write settings device 1
#define SMI_DSR2 0x20 // Read settings device 2
#define SMI_DSW2 0x24 // Write settings device 2
#define SMI_DSR3 0x28 // Read settings device 3
#define SMI_DSW3 0x2c // Write settings device 3
#define SMI_DMC 0x30 // DMA control
#define SMI_DCS 0x34 // Direct control/status
#define SMI_DCA 0x38 // Direct address
#define SMI_DCD 0x3c // Direct data
#define SMI_FD 0x40 // FIFO debug
#define SMI_REGLEN (SMI_FD * 4)
// Data widths
#define SMI_8_BITS 0
#define SMI_16_BITS 1
#define SMI_18_BITS 2
#define SMI_9_BITS 3
// DMA request
#define DMA_SMI_DREQ 4
// Union of 32-bit value with register bitfields
#define REG_DEF(name, fields) typedef union {struct {volatile uint32_t fields;}; volatile uint32_t value;} name
// Control and status register
#define SMI_CS_FIELDS \
enable:1, done:1, active:1, start:1, clear:1, write:1, _x1:2,\
teen:1, intd:1, intt:1, intr:1, pvmode:1, seterr:1, pxldat:1, edreq:1,\
_x2:8, _x3:1, aferr:1, txw:1, rxr:1, txd:1, rxd:1, txe:1, rxf:1
REG_DEF(SMI_CS_REG, SMI_CS_FIELDS);
// Data length register
#define SMI_L_FIELDS \
len:32
REG_DEF(SMI_L_REG, SMI_L_FIELDS);
// Address & device number
#define SMI_A_FIELDS \
addr:6, _x1:2, dev:2
REG_DEF(SMI_A_REG, SMI_A_FIELDS);
// Data FIFO
#define SMI_D_FIELDS \
data:32
REG_DEF(SMI_D_REG, SMI_D_FIELDS);
// DMA control register
#define SMI_DMC_FIELDS \
reqw:6, reqr:6, panicw:6, panicr:6, dmap:1, _x1:3, dmaen:1
REG_DEF(SMI_DMC_REG, SMI_DMC_FIELDS);
// Device settings: read (1 of 4)
#define SMI_DSR_FIELDS \
rstrobe:7, rdreq:1, rpace:7, rpaceall:1, \
rhold:6, fsetup:1, mode68:1, rsetup:6, rwidth:2
REG_DEF(SMI_DSR_REG, SMI_DSR_FIELDS);
// Device settings: write (1 of 4)
#define SMI_DSW_FIELDS \
wstrobe:7, wdreq:1, wpace:7, wpaceall:1, \
whold:6, wswap:1, wformat:1, wsetup:6, wwidth:2
REG_DEF(SMI_DSW_REG, SMI_DSW_FIELDS);
// Direct control register
#define SMI_DCS_FIELDS \
enable:1, start:1, done:1, write:1
REG_DEF(SMI_DCS_REG, SMI_DCS_FIELDS);
// Direct control address & device number
#define SMI_DCA_FIELDS \
addr:6, _x1:2, dev:2
REG_DEF(SMI_DCA_REG, SMI_DCA_FIELDS);
// Direct control data
#define SMI_DCD_FIELDS \
data:32
REG_DEF(SMI_DCD_REG, SMI_DCD_FIELDS);
// Debug register
#define SMI_FLVL_FIELDS \
fcnt:6, _x1:2, flvl:6
REG_DEF(SMI_FLVL_REG, SMI_FLVL_FIELDS);
#define CLK_SMI_CTL 0xb0
#define CLK_SMI_DIV 0xb4
// EOF