纯FPGA实现AD9361控制的思路和实现 UART实现AXI_MASTER

发布于:2025-04-20 ⋅ 阅读:(20) ⋅ 点赞:(0)

 

这里用一个串口接收PC机传过来的读写寄存器的控制指令,对地址地址的AXI_sLAVE进行读写后返回其结果。

串口收发器用的代码还是经典的FPGA4FUN上的。fpga4fun.com - Serial interface (RS-232)

我做了极小修改,直接贴出来代码:


// RS-232 RX and TX module
// (c) fpga4fun.com & KNJN LLC - 2003 to 2016

// The RS-232 settings are fixed
// TX: 8-bit data, 2 stop, no-parity
// RX: 8-bit data, 1 stop, no-parity (the receiver can accept more stop bits of course)

//`define SIMULATION   // in this mode, TX outputs one bit per clock cycle
                       // and RX receives one bit per clock cycle (for fast simulations)


module async_transmitter(
	input clk,
	input TxD_start,
	input [7:0] TxD_data,
	output TxD,
	output TxD_busy
);

// Assert TxD_start for (at least) one clock cycle to start transmission of TxD_data
// TxD_data is latched so that it doesn't have to stay valid while it is being sent

parameter ClkFrequency = 1000*1000*100; // 100MHz
parameter Baud = 115200;

generate
	if(ClkFrequency<Baud*8 && (ClkFrequency % Baud!=0)) ASSERTION_ERROR PARAMETER_OUT_OF_RANGE("Frequency incompatible with requested Baud rate");
endgenerate


`ifdef SIMULATION
wire BitTick = 1'b1;  // output one bit per clock cycle
`else
wire BitTick;
BaudTickGen #(ClkFrequency, Baud) tickgen(.clk(clk), .enable(TxD_busy), .tick(BitTick));
`endif

reg [3:0] TxD_state = 0;
wire TxD_ready = (TxD_state==0);
assign TxD_busy = ~TxD_ready;

reg [7:0] TxD_shift = 0;
always @(posedge clk)
begin
	if(TxD_ready & TxD_start)
		TxD_shift <= TxD_data;
	else
	if(TxD_state[3] & BitTick)
		TxD_shift <= (TxD_shift >> 1);

	case(TxD_state)
		4'b0000: if(TxD_start) TxD_state <= 4'b0100;
		4'b0100: if(BitTick) TxD_state <= 4'b1000;  // start bit
		4'b1000: if(BitTick) TxD_state <= 4'b1001;  // bit 0
		4'b1001: if(BitTick) TxD_state <= 4'b1010;  // bit 1
		4'b1010: if(BitTick) TxD_state <= 4'b1011;  // bit 2
		4'b1011: if(BitTick) TxD_state <= 4'b1100;  // bit 3
		4'b1100: if(BitTick) TxD_state <= 4'b1101;  // bit 4
		4'b1101: if(BitTick) TxD_state <= 4'b1110;  // bit 5
		4'b1110: if(BitTick) TxD_state <= 4'b1111;  // bit 6
		4'b1111: if(BitTick) TxD_state <= 4'b0010;  // bit 7
		4'b0010: if(BitTick) TxD_state <= 4'b0011;  // stop1
		4'b0011: if(BitTick) TxD_state <= 4'b0000;  // stop2
		default: if(BitTick) TxD_state <= 4'b0000;
	endcase
end

assign TxD = (TxD_state<4) | (TxD_state[3] & TxD_shift[0]);  // put together the start, data and stop bits
endmodule



module async_receiver(
	input clk,
	input RxD,
	output reg RxD_data_ready = 0,
	output reg [7:0] RxD_data = 0,  // data received, valid only (for one clock cycle) when RxD_data_ready is asserted

	// We also detect if a gap occurs in the received stream of characters
	// That can be useful if multiple characters are sent in burst
	//  so that multiple characters can be treated as a "packet"
	output RxD_idle,  // asserted when no data has been received for a while
	output reg RxD_endofpacket = 0  // asserted for one clock cycle when a packet has been detected (i.e. RxD_idle is going high)
);

parameter ClkFrequency = 1000*1000*100; // 100MHz
parameter Baud = 115200;

parameter Oversampling = 8;  // needs to be a power of 2
// we oversample the RxD line at a fixed rate to capture each RxD data bit at the "right" time
// 8 times oversampling by default, use 16 for higher quality reception

generate
	if(ClkFrequency<Baud*Oversampling) ASSERTION_ERROR PARAMETER_OUT_OF_RANGE("Frequency too low for current Baud rate and oversampling");
	if(Oversampling<8 || ((Oversampling & (Oversampling-1))!=0)) ASSERTION_ERROR PARAMETER_OUT_OF_RANGE("Invalid oversampling value");
endgenerate


reg [3:0] RxD_state = 0;

`ifdef SIMULATION
wire RxD_bit = RxD;
wire sampleNow = 1'b1;  // receive one bit per clock cycle

`else
wire OversamplingTick;
BaudTickGen #(ClkFrequency, Baud, Oversampling) tickgen(.clk(clk), .enable(1'b1), .tick(OversamplingTick));

// synchronize RxD to our clk domain
reg [1:0] RxD_sync = 2'b11;
always @(posedge clk) if(OversamplingTick) RxD_sync <= {RxD_sync[0], RxD};

// and filter it
reg [1:0] Filter_cnt = 2'b11;
reg RxD_bit = 1'b1;

always @(posedge clk)
if(OversamplingTick)
begin
	if(RxD_sync[1]==1'b1 && Filter_cnt!=2'b11) Filter_cnt <= Filter_cnt + 1'd1;
	else 
	if(RxD_sync[1]==1'b0 && Filter_cnt!=2'b00) Filter_cnt <= Filter_cnt - 1'd1;

	if(Filter_cnt==2'b11) RxD_bit <= 1'b1;
	else
	if(Filter_cnt==2'b00) RxD_bit <= 1'b0;
end

// and decide when is the good time to sample the RxD line
function integer log2(input integer v); begin log2=0; while(v>>log2) log2=log2+1; end endfunction
localparam l2o = log2(Oversampling);
reg [l2o-2:0] OversamplingCnt = 0;
always @(posedge clk) if(OversamplingTick) OversamplingCnt <= (RxD_state==0) ? 1'd0 : OversamplingCnt + 1'd1;
wire sampleNow = OversamplingTick && (OversamplingCnt==Oversampling/2-1);
`endif

// now we can accumulate the RxD bits in a shift-register
always @(posedge clk)
case(RxD_state)
	4'b0000: if(~RxD_bit) RxD_state <= `ifdef SIMULATION 4'b1000 `else 4'b0001 `endif;  // start bit found?
	4'b0001: if(sampleNow) RxD_state <= 4'b1000;  // sync start bit to sampleNow
	4'b1000: if(sampleNow) RxD_state <= 4'b1001;  // bit 0
	4'b1001: if(sampleNow) RxD_state <= 4'b1010;  // bit 1
	4'b1010: if(sampleNow) RxD_state <= 4'b1011;  // bit 2
	4'b1011: if(sampleNow) RxD_state <= 4'b1100;  // bit 3
	4'b1100: if(sampleNow) RxD_state <= 4'b1101;  // bit 4
	4'b1101: if(sampleNow) RxD_state <= 4'b1110;  // bit 5
	4'b1110: if(sampleNow) RxD_state <= 4'b1111;  // bit 6
	4'b1111: if(sampleNow) RxD_state <= 4'b0010;  // bit 7
	4'b0010: if(sampleNow) RxD_state <= 4'b0000;  // stop bit
	default: RxD_state <= 4'b0000;
endcase

always @(posedge clk)
if(sampleNow && RxD_state[3]) RxD_data <= {RxD_bit, RxD_data[7:1]};

//reg RxD_data_error = 0;
always @(posedge clk)
begin
	RxD_data_ready <= (sampleNow && RxD_state==4'b0010 && RxD_bit);  // make sure a stop bit is received
	//RxD_data_error <= (sampleNow && RxD_state==4'b0010 && ~RxD_bit);  // error if a stop bit is not received
end

`ifdef SIMULATION
assign RxD_idle = 0;
`else
reg [l2o+1:0] GapCnt = 0;
always @(posedge clk) if (RxD_state!=0) GapCnt<=0; else if(OversamplingTick & ~GapCnt[log2(Oversampling)+1]) GapCnt <= GapCnt + 1'h1;
assign RxD_idle = GapCnt[l2o+1];
always @(posedge clk) RxD_endofpacket <= OversamplingTick & ~GapCnt[l2o+1] & &GapCnt[l2o:0];
`endif

endmodule



// dummy module used to be able to raise an assertion in Verilog
module ASSERTION_ERROR();
endmodule



module BaudTickGen(
	input clk, enable,
	output tick  // generate a tick at the specified baud rate * oversampling
);
parameter ClkFrequency = 25000000;
parameter Baud = 115200;
parameter Oversampling = 1;

function integer log2(input integer v); begin log2=0; while(v>>log2) log2=log2+1; end endfunction
localparam AccWidth = log2(ClkFrequency/Baud)+8;  // +/- 2% max timing error over a byte
reg [AccWidth:0] Acc = 0;
localparam ShiftLimiter = log2(Baud*Oversampling >> (31-AccWidth));  // this makes sure Inc calculation doesn't overflow
localparam Inc = ((Baud*Oversampling << (AccWidth-ShiftLimiter))+(ClkFrequency>>(ShiftLimiter+1)))/(ClkFrequency>>ShiftLimiter);
always @(posedge clk) if(enable) Acc <= Acc[AccWidth-1:0] + Inc[AccWidth:0]; else Acc <= Inc[AccWidth:0];
assign tick = Acc[AccWidth];
endmodule



我写的代码就是下面的这个状态机:


/*

uart2bus32 uart2bus32(
.clk( ) ,
.rst( ) ,

.uart_in_u8( ) ,
.uart_in_valid( ) ,

.uart_out_u8( ) ,
.uart_out_valid( ) ,
.uart_out_busy( ) ,

.addr ( ) ,
.wr_u32( ) ,
.wr_vaild( ) ,
.wr_ready( ) ,
.wr_err( ) ,

.rd_addr_valid ( ) ,
.rd_done ( ) ,
.rd_err( ) ,
.rd_u32 ( ) 
);

*/

module uart2bus32(
input clk,rst,

input [7:0]  uart_in_u8,
input uart_in_valid,

output reg [31:0]  uart_out_u8,
output reg uart_out_valid,
input uart_out_busy,


output reg [31:0] addr ,
output reg [31:0]  wr_u32,
output reg wr_vaild,
input wr_ready,wr_err,

output reg  rd_addr_valid ,
input rd_done ,rd_err,
input[31:0]  rd_u32 ,
output reg [7:0]  st 
);

reg wr_err_r ; always@(posedge clk) if (wr_ready)wr_err_r <= wr_err ; 

function [7:0] chksum_u32;input [31:0] u ;begin chksum_u32 =  u[31:24] + u[23:16] +u[15:8] + u[7:0]  ; end endfunction 
 
reg [7:0]addr_chksum ;
reg [3:0] c;
reg [7:0] delay ;
reg [31:0]rd_u32_r;
reg [7:0] rd_u32_chksum;always @(posedge clk) addr_chksum <=chksum_u32( addr); 
reg [7:0] wr_u32_chksum ;always@(posedge clk )wr_u32_chksum <= chksum_u32(wr_u32) + addr_chksum ;

always @(posedge clk) case (st)  44:delay <= delay+1;default delay<=0;endcase 
reg [7:0] cmd ; always@(posedge clk) if (st==12) cmd<=uart_in_u8 ;  

always @(posedge clk) if (rst) st<=5;else case(st)
0   :  st <= 5 ;
5   :  st <= 10 ;
10 :  if (uart_in_valid) st<= (uart_in_u8 ==  'h55 ) ?(st+1): 10;
11 :  if (uart_in_valid) st<= (uart_in_u8 ==  'haa ) ?(st+1): 10;
12 :  if (uart_in_valid) case (uart_in_u8)3,5:st<=30;default st<=10;endcase 

30,31,32,33:if (uart_in_valid) st<= st+1;
34:if (cmd ==3 ) st<=st+1;else st<=50;
35:if (uart_in_valid)  st<=( addr_chksum == uart_in_u8 ) ? 40: 10;
40:st<=st+1;// read function 
41:if ( rd_done ) st<=st+1; 
42:if (uart_out_busy==0) st<=st+1;
43:st<=st+1; // do write 
44:if (delay==10)  st<=st+1;
45:st<=st+1; 
46:if (c!=5) st<=42;else st<=st+1;//c++
47:st<=st+1;
48:st<= 10;   

50,51,52,53:if (uart_in_valid) st<=st+1;
54: if(uart_in_valid) st<=(wr_u32_chksum==uart_in_u8) ? 55 : 1059;
55: st<=st+1;// set as valid
56: if ( wr_ready ) st<=st+1;
57: st<=st+1;
58: if ( uart_out_busy ==0)  st<=st+1; 
59: st<=10;

default st<=0;endcase 

always @(*) wr_vaild = st== 55 ;
always @(posedge clk) if (st==30)  addr[31:24]    <= uart_in_u8;
always @(posedge clk) if (st==31)  addr[23:16]    <= uart_in_u8;
always @(posedge clk) if (st==32)  addr[15:8]     <= uart_in_u8;
always @(posedge clk) if (st==33)  addr[7:0]      <= uart_in_u8;

always @(posedge clk) if (st==50)  wr_u32[31:24] <= uart_in_u8;
always @(posedge clk) if (st==51)  wr_u32[23:16] <= uart_in_u8;
always @(posedge clk) if (st==52)  wr_u32[15:8]  <= uart_in_u8;
always @(posedge clk) if (st==53)  wr_u32[7:0]   <= uart_in_u8;
 
always @(*)rd_addr_valid= st==40 ;

always @(posedge clk) if ( rd_done )rd_u32_r  <= rd_u32 ;
reg rd_err_r ;  always @(posedge clk) if ( rd_done)rd_err_r  <= rd_err ;

always @(posedge clk)rd_u32_chksum  <=chksum_u32( rd_u32_r) + {7'b0,rd_err_r}; 
always @(posedge clk)case (st) 40:c<=0;46:c<=c+1;default c<=c;endcase
always @(posedge clk)uart_out_valid <=  (st==43)||(st==59) ;

always @(posedge clk)if (st==43)case (c) 
0 : uart_out_u8 <=  rd_u32_r [31:24] ; 
1 : uart_out_u8 <=  rd_u32_r [23:16] ;
2 : uart_out_u8 <=  rd_u32_r [15:8] ;
3 : uart_out_u8 <=  rd_u32_r [7:0] ;
5 : uart_out_u8 <=  rd_u32_chksum ;
4 : uart_out_u8 <= {7'b0,rd_err_r};
endcase else if (st==59)  uart_out_u8<={7'b0,wr_err_r}; else uart_out_u8 <= 0 ;

endmodule 


这个代码还是实现了CHECKSUM校验。

对应的PC端代码如下:

#include <stdio.h>
#include <string.h>
#include <sys/types.h>
#include <errno.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <unistd.h>
#include <termios.h>
#include <stdlib.h>
#include<sys/stat.h>
#include<fcntl.h>
#include<errno.h>
#include<netdb.h>
#include<sys/types.h>
#include<sys/socket.h>
#include<netinet/in.h>
#include<arpa/inet.h>
#include<string.h>
#include<stdlib.h>
#include<stdio.h>
#include<unistd.h>
#include<stdarg.h>
#include <sys/select.h>
#include <sys/time.h>


void sdrpi_dev_init(int port ){
 int r = serial_open(port ,115200); 
if (r<0){
printf("can not open serial,so exit \n");
exit(-1);
}
}

static unsigned char get_byte(unsigned int u,int idx){
unsigned char r0,r1,r2,r3 ;
r0=u&0xff; u>>=8;
r1=u&0xff; u>>=8;
r2=u&0xff; u>>=8;
r3=u&0xff;

if (idx==0)return r0;else 
if (idx==1)return r1;else 
if (idx==2)return r2;else 
if (idx==3)return r3;
}



unsigned int uart2master_wr(unsigned int addr ,unsigned int dat){
static  unsigned char buff[20] ={0};
unsigned int  sum = 0  ;
unsigned int r ; 
int i ;
for(i=0;i<20;++i)buff[i]=0;
serial_write(buff,12);
buff[0]=0x55;   
buff[1]=0xaa;
buff[2]=0x05; // write command 

buff[3]=get_byte(addr,3);
buff[4]=get_byte(addr,2);
buff[5]=get_byte(addr,1);
buff[6]=get_byte(addr,0);

buff[7] =get_byte(dat,3); 
buff[8] =get_byte(dat,2);
buff[9] =get_byte(dat,1);
buff[10]=get_byte(dat,0);

for(sum=0,i=3;i<=10;++i) sum += buff[i] ;
buff[11]=sum &0xff;
serial_write(buff,12);
buff[0] = serial_try_getc(&i);if (i==0) { printf("wr: can not read serial,so exit \n");exit(-1); } 
r = buff[0] ; 
return r ; 

} checked OK
 


unsigned int uart2master_rd(unsigned int addr ){

static  unsigned char buff[20];
unsigned char   sum = 0  ;
unsigned int r ; 
int i ;
buff[0]=0x55;   
buff[1]=0xaa;
buff[2]=0x03; // read command 

buff[3]=get_byte(addr,3);
buff[4]=get_byte(addr,2);
buff[5]=get_byte(addr,1);
buff[6]=get_byte(addr,0);
 

for(sum=0,i=3;i<=6;++i) sum+=buff[i];
buff[7]=sum&0xff ;

serial_write(buff,8);

buff[0] = serial_try_getc(&i); if ( i == 0 ) { printf("1 can not read serial,so exit \n");exit(-1); } ;//[31:24]
buff[1] = serial_try_getc(&i); if ( i == 0 ) { printf("2 can not read serial,so exit \n");exit(-1); } ;//[23:16]
buff[2] = serial_try_getc(&i); if ( i == 0 ) { printf("3 can not read serial,so exit \n");exit(-1); } ;//[15:8]
buff[3] = serial_try_getc(&i); if ( i == 0 ) { printf("3 can not read serial,so exit \n");exit(-1); } ;//[7:0]
buff[4] = serial_try_getc(&i); if ( i == 0 ) { printf("4 can not read serial,so exit \n");exit(-1); } ;//ERROR
buff[5] = serial_try_getc(&i); if ( i == 0 ) { printf("5 can not read serial,so exit \n");exit(-1); } ;//CHKSUM

for(sum=0,i=0;i<=4;++i) sum+=buff[i];
 if ( buff[5] != sum )  { printf("uart2master_rd check sum error local sum is %02x %02x  \n",buff[5],sum &0xff); exit(-1);}
if (buff[4])printf("err bit is %d \n",buff[4]);

r  = buff[0] ; r <<= 8 ;
r |= buff[1] ; r <<= 8 ;
r |= buff[2] ; r <<= 8 ;
r |= buff[3] ;  

return r ; 

}


void test_reg_loop (unsigned int addr ,unsigned int c){
unsigned int  r ,t; 
sdrpi_dev_init(0);
t = 0xabcdef01 ;
while(c--) {
t++;
uart2master_wr(addr,t);
r = uart2master_rd(addr);
printf("r = %08X\n",r);
if ( t != r){  printf("1 %08X   %08X  \n",t,r);exit(-1);} 
}
printf("test_reg_loop test passed. \n");
}











这里也同时贴出来LINUX下串口操作的代码:

#include <stdio.h>


#include <string.h>

#include <sys/types.h>

#include <errno.h>

#include <sys/stat.h>

#include <fcntl.h>

#include <unistd.h>

#include <termios.h>

#include <stdlib.h>







#include<sys/stat.h>

#include<fcntl.h>

#include<errno.h>

#include<netdb.h>

#include<sys/types.h>

#include<sys/socket.h>

#include<netinet/in.h>

#include<arpa/inet.h>

#include<string.h>

#include<stdlib.h>

#include<stdio.h>

#include<unistd.h>

#include<stdarg.h>




#include <sys/select.h>

#include <sys/time.h>




static int fd;




static int set_opt( int nSpeed, int nBits, char nEvent, int nStop)

{

    struct termios newtio,oldtio;

    if  ( tcgetattr( fd,&oldtio)  !=  0) 

    { 

        perror("SetupSerial 1");

        return -1;

    }

    bzero( &newtio, sizeof( newtio ) );

    newtio.c_cflag  |=  CLOCAL | CREAD; 

    newtio.c_cflag &= ~CSIZE; 




    switch( nBits )

    {

    case 7:

        newtio.c_cflag |= CS7;

        break;

    case 8:

        newtio.c_cflag |= CS8;

        break;

    }




    switch( nEvent )

    {

    case 'O':                     //奇校验

        newtio.c_cflag |= PARENB;

        newtio.c_cflag |= PARODD;

        newtio.c_iflag |= (INPCK | ISTRIP);

        break;

    case 'E':                     //偶校验

        newtio.c_iflag |= (INPCK | ISTRIP);

        newtio.c_cflag |= PARENB;

        newtio.c_cflag &= ~PARODD;

        break;

    case 'N':                    //无校验

        newtio.c_cflag &= ~PARENB;

        break;

    }




switch( nSpeed )

    {

    case 2400:

        cfsetispeed(&newtio, B2400);

        cfsetospeed(&newtio, B2400);

        break;

    case 4800:

        cfsetispeed(&newtio, B4800);

        cfsetospeed(&newtio, B4800);

        break;

    case 9600:

        cfsetispeed(&newtio, B9600);

        cfsetospeed(&newtio, B9600);

        break;

    case 115200:

        cfsetispeed(&newtio, B115200);

        cfsetospeed(&newtio, B115200);

        break;

    default:

        cfsetispeed(&newtio, B9600);

        cfsetospeed(&newtio, B9600);

        break;

    }

    if( nStop == 1 )

    {

        newtio.c_cflag &=  ~CSTOPB;

    }

    else if ( nStop == 2 )

    {

        newtio.c_cflag |=  CSTOPB;

    }

    newtio.c_cc[VTIME]  = 0;

    newtio.c_cc[VMIN] = 0;

    tcflush(fd,TCIFLUSH);

    if((tcsetattr(fd,TCSANOW,&newtio))!=0)

    {

        perror("com set error");

        return -1;

    }

    printf("set done!\n");

    return 0;

}







static int open_port( int comport)

{




    long  vdisable;

	char port_name[100] ;

		sprintf(port_name,"/dev/ttyUSB%d",comport);

        //  fd = open( "/dev/ttyUSB0", O_RDWR);

       fd = open( port_name, O_RDWR|O_NOCTTY |O_NDELAY);

        if (-1 == fd)

        {

            perror("Can't Open Serial Port");

            return(-1);

        }

        else 

        {

            printf("open ttyUSB0 .....\n");

        }

  

    if(fcntl(fd, F_SETFL, 0)<0)

    {

        printf("fcntl failed!\n");

    }

    else

    {

        printf("fcntl=%d\n",fcntl(fd, F_SETFL,0));

    }

    if(isatty(STDIN_FILENO)==0)

    {

        printf("standard input is not a terminal device\n");

    }

    else

    {

        printf("isatty success!\n");

    }







    printf("fd-open=%d\n",fd);

 

    return fd;

}













  int serial_open (int i ,unsigned int baund ){




   

    if((fd=open_port(i))<0)

    {

        perror("open_port error");

        return -1;

    }







    if((i=set_opt(baund,8,'N',2))<0)

    {

        perror("set_opt error");

        return -1 ;

    }

    printf("fd=%d\n",fd);

return 0 ;

}







  int serial_write(char * buf , int len ){

return write(fd,buf,len);

}













static int is_serial_ready(int fd)

{

  /*

  利用SELECT监视端口数据就可以

fd_set fds;

timeval timeout={3,0}; //select等待3秒

FD_ZERO(&fds); //每次循环都要清空集合,否则不能检测描述符变化

FD_SET(m_CSocket,&fds); //添加描述符

int sel=select(m_CSocket+1,&fds,NULL,NULL,&timeout);

在等待的timeout时间内,若端口有数据,则select函数会返回,通过判断sel的值,就知道端口是否有数据,或者是超时了。

*/

    int rc ;
    fd_set fds ;
    struct timeval tv ;
    //printf("enter is_ready   %d\n",cnt++);
    tv.tv_sec=3 ;
    tv.tv_usec=2;
    FD_ZERO(&fds);
    FD_SET(fd,&fds);
    rc=select(fd+1,&fds,NULL,NULL,&tv);
    //printf("out is ready   res =%d \n",rc);
    if(rc<0)
    return -1 ;
    rc=FD_ISSET(fd,&fds)?1:0 ;
    //printf(" result is  =%d \n",rc);
    return rc ;
}










static char  serial_getchar(){
char ch ;    
while(read(fd,&ch ,1)==0); 
 return ch ;
}







static  int serial_read(char * buf,int len ){
int i;
for(i=0;i<len;++i)buf[i] = serial_getchar() ; 
return len;
}







unsigned char  serial_try_getc (int *valid ){
	*valid=0;
if (is_serial_ready(fd)==0) return 0XFF ;
*valid=1;
return serial_getchar();
}

 

int serial_putc(char c){

static char buf[2];buf[0]=c;	

return write(fd,buf,1);

}




 

 

 

 

 

 

 

 

 

 

 

 

 


网站公告

今日签到

点亮在社区的每一天
去签到