diff options
-rw-r--r-- | rs422lib/lnk_msp430g2553.cmd | 132 | ||||
-rw-r--r-- | rs422lib/main.c | 43 | ||||
-rw-r--r-- | rs422lib/precomp.h | 28 | ||||
-rw-r--r-- | rs422lib/rsbus.c | 201 | ||||
-rw-r--r-- | rs422lib/rsbus.h | 41 | ||||
-rw-r--r-- | rs422lib/sysctl.c | 87 | ||||
-rw-r--r-- | rs422lib/sysctl.h | 38 |
7 files changed, 570 insertions, 0 deletions
diff --git a/rs422lib/lnk_msp430g2553.cmd b/rs422lib/lnk_msp430g2553.cmd new file mode 100644 index 0000000..3d6ce8e --- /dev/null +++ b/rs422lib/lnk_msp430g2553.cmd @@ -0,0 +1,132 @@ +/* ============================================================================ */ +/* Copyright (c) 2013, Texas Instruments Incorporated */ +/* All rights reserved. */ +/* */ +/* Redistribution and use in source and binary forms, with or without */ +/* modification, are permitted provided that the following conditions */ +/* are met: */ +/* */ +/* * Redistributions of source code must retain the above copyright */ +/* notice, this list of conditions and the following disclaimer. */ +/* */ +/* * Redistributions in binary form must reproduce the above copyright */ +/* notice, this list of conditions and the following disclaimer in the */ +/* documentation and/or other materials provided with the distribution. */ +/* */ +/* * Neither the name of Texas Instruments Incorporated nor the names of */ +/* its contributors may be used to endorse or promote products derived */ +/* from this software without specific prior written permission. */ +/* */ +/* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" */ +/* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, */ +/* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR */ +/* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR */ +/* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, */ +/* EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, */ +/* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; */ +/* OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, */ +/* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR */ +/* OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, */ +/* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ +/* ============================================================================ */ + +/******************************************************************************/ +/* lnk_msp430g2553.cmd - LINKER COMMAND FILE FOR LINKING MSP430G2553 PROGRAMS */ +/* */ +/* Usage: lnk430 <obj files...> -o <out file> -m <map file> lnk.cmd */ +/* cl430 <src files...> -z -o <out file> -m <map file> lnk.cmd */ +/* */ +/*----------------------------------------------------------------------------*/ +/* These linker options are for command line linking only. For IDE linking, */ +/* you should set your linker options in Project Properties */ +/* -c LINK USING C CONVENTIONS */ +/* -stack 0x0100 SOFTWARE STACK SIZE */ +/* -heap 0x0100 HEAP AREA SIZE */ +/* */ +/*----------------------------------------------------------------------------*/ + + +/****************************************************************************/ +/* SPECIFY THE SYSTEM MEMORY MAP */ +/****************************************************************************/ + +MEMORY +{ + SFR : origin = 0x0000, length = 0x0010 + PERIPHERALS_8BIT : origin = 0x0010, length = 0x00F0 + PERIPHERALS_16BIT : origin = 0x0100, length = 0x0100 + RAM : origin = 0x0200, length = 0x0200 + INFOA : origin = 0x10C0, length = 0x0040 + INFOB : origin = 0x1080, length = 0x0040 + INFOC : origin = 0x1040, length = 0x0040 + INFOD : origin = 0x1000, length = 0x0040 + FLASH : origin = 0xC000, length = 0x3FE0 + INT00 : origin = 0xFFE0, length = 0x0002 + INT01 : origin = 0xFFE2, length = 0x0002 + INT02 : origin = 0xFFE4, length = 0x0002 + INT03 : origin = 0xFFE6, length = 0x0002 + INT04 : origin = 0xFFE8, length = 0x0002 + INT05 : origin = 0xFFEA, length = 0x0002 + INT06 : origin = 0xFFEC, length = 0x0002 + INT07 : origin = 0xFFEE, length = 0x0002 + INT08 : origin = 0xFFF0, length = 0x0002 + INT09 : origin = 0xFFF2, length = 0x0002 + INT10 : origin = 0xFFF4, length = 0x0002 + INT11 : origin = 0xFFF6, length = 0x0002 + INT12 : origin = 0xFFF8, length = 0x0002 + INT13 : origin = 0xFFFA, length = 0x0002 + INT14 : origin = 0xFFFC, length = 0x0002 + RESET : origin = 0xFFFE, length = 0x0002 +} + +/****************************************************************************/ +/* SPECIFY THE SECTIONS ALLOCATION INTO MEMORY */ +/****************************************************************************/ + +SECTIONS +{ + .bss : {} > RAM /* GLOBAL & STATIC VARS */ + .data : {} > RAM /* GLOBAL & STATIC VARS */ + .sysmem : {} > RAM /* DYNAMIC MEMORY ALLOCATION AREA */ + .stack : {} > RAM (HIGH) /* SOFTWARE SYSTEM STACK */ + + .text : {} > FLASH /* CODE */ + .cinit : {} > FLASH /* INITIALIZATION TABLES */ + .const : {} > FLASH /* CONSTANT DATA */ + .cio : {} > RAM /* C I/O BUFFER */ + + .pinit : {} > FLASH /* C++ CONSTRUCTOR TABLES */ + .init_array : {} > FLASH /* C++ CONSTRUCTOR TABLES */ + .mspabi.exidx : {} > FLASH /* C++ CONSTRUCTOR TABLES */ + .mspabi.extab : {} > FLASH /* C++ CONSTRUCTOR TABLES */ + + .infoA : {} > INFOA /* MSP430 INFO FLASH MEMORY SEGMENTS */ + .infoB : {} > INFOB + .infoC : {} > INFOC + .infoD : {} > INFOD + + /* MSP430 INTERRUPT VECTORS */ + .int00 : {} > INT00 + .int01 : {} > INT01 + PORT1 : { * ( .int02 ) } > INT02 type = VECT_INIT + PORT2 : { * ( .int03 ) } > INT03 type = VECT_INIT + .int04 : {} > INT04 + ADC10 : { * ( .int05 ) } > INT05 type = VECT_INIT + USCIAB0TX : { * ( .int06 ) } > INT06 type = VECT_INIT + USCIAB0RX : { * ( .int07 ) } > INT07 type = VECT_INIT + TIMER0_A1 : { * ( .int08 ) } > INT08 type = VECT_INIT + TIMER0_A0 : { * ( .int09 ) } > INT09 type = VECT_INIT + WDT : { * ( .int10 ) } > INT10 type = VECT_INIT + COMPARATORA : { * ( .int11 ) } > INT11 type = VECT_INIT + TIMER1_A1 : { * ( .int12 ) } > INT12 type = VECT_INIT + TIMER1_A0 : { * ( .int13 ) } > INT13 type = VECT_INIT + NMI : { * ( .int14 ) } > INT14 type = VECT_INIT + .reset : {} > RESET /* MSP430 RESET VECTOR */ +} + +/****************************************************************************/ +/* INCLUDE PERIPHERALS MEMORY MAP */ +/****************************************************************************/ + +-l msp430g2553.cmd + diff --git a/rs422lib/main.c b/rs422lib/main.c new file mode 100644 index 0000000..8f6ec49 --- /dev/null +++ b/rs422lib/main.c @@ -0,0 +1,43 @@ + +#include"precomp.h" +#include"rsbus.h" +#include"sysctl.h" + +void port_init(void) +{ + P1DIR |= BIT0+BIT6; // P1.0 P1.6 output + P1OUT = 0; +} + +void received(unsigned char* str,int len) +{ + rsbus_w(0,str,len); +} + +void init_devices(void) +{ + WDTCTL = WDTPW + WDTHOLD; // Stop watchdog timer + + if (CALBC1_8MHZ ==0xFF || CALDCO_8MHZ == 0xFF) + while(1)_BIS_SR(CPUOFF); // If calibration constants erased, trap CPU!! + + BCSCTL1 = CALBC1_16MHZ; // Set range + DCOCTL = CALDCO_16MHZ; // Set DCO step + modulation£¬DCO=8MHz + BCSCTL3 |= LFXT1S_2; // LFXT1 = VLO + IFG1 &= ~OFIFG; // Clear OSCFault flag + BCSCTL2 |= DIVS_2; // SMCLK = DCO/4 = 4MHz + + sysctl_init(); + port_init(); + rsbus_init(&received); + + _BIS_SR(GIE); +} + +void main(void) +{ + init_devices(); + while(1) + sysroutine(); +} + diff --git a/rs422lib/precomp.h b/rs422lib/precomp.h new file mode 100644 index 0000000..3c7c016 --- /dev/null +++ b/rs422lib/precomp.h @@ -0,0 +1,28 @@ +/*
+ * precomp.h
+ *
+ * Created on: 2014-4-26
+ * Author: Tuowen
+ */
+
+#ifndef PRECOMP_H_
+#define PRECOMP_H_
+
+#include<msp430g2553.h>
+
+#define RSDIR (P1DIR)
+#define RSOUT (P1OUT)
+#define RSPIN (BIT0)
+
+#define RSSYSBIT (SYS_BIT7) // This is the lowest level
+#define RSSYSRET (SYS_BIT6) // Second lowest level
+
+#define RSADDR (1)
+
+#define MACTYPE (TYPE0)
+// Change it in real implementation
+
+//define delay func
+#define delay_ms(ms) __delay_cycles(16000*(ms))
+
+#endif /* PRECOMP_H_ */
diff --git a/rs422lib/rsbus.c b/rs422lib/rsbus.c new file mode 100644 index 0000000..705736f --- /dev/null +++ b/rs422lib/rsbus.c @@ -0,0 +1,201 @@ +/*
+ * rsbus.c
+ *
+ * Created on: 2014-4-26
+ * Author: Tuowen
+ */
+#include "rsbus.h"
+#include "sysctl.h"
+
+#define SYSRET (0xF0)
+#define INSREP (0x0F)
+
+unsigned char rs_rxbuf[RSMAX];
+unsigned char len;
+unsigned char pch;
+unsigned char ret;
+rshdlr rxhdlr;
+enum rs_stat{REST,ST,ADDR,READ,DISCARD,ED,DED};
+enum rs_stat rs_st=REST;
+
+unsigned char rs_tx[12]={STBIT1,0,RSADDR,MACTYPE,0,0,0,0,0,0,0,0};
+unsigned char tx_len;
+unsigned char tx_pos;
+
+#pragma vector=USCIAB0TX_VECTOR
+__interrupt void USCI0TX_ISR(void)
+{
+ if (tx_pos == tx_len) // TX over?
+ {
+ UC0IE &= ~UCA0TXIE; // Disable USCI_A0 TX interrupt
+ RSOUT &= ~(RSPIN);
+ }
+ else
+ UCA0TXBUF = rs_tx[tx_pos++]; // TX next character
+}
+
+#pragma vector=USCIAB0RX_VECTOR
+__interrupt void rsbus_rx(void)
+{
+ //IFG2&=(~UCA0RXIFG);
+ int dat;
+ dat=UCA0RXBUF;
+ /************ Simple State Machine *************/
+ switch (rs_st)
+ {
+ case REST:
+ rs_st=(dat==STBIT0)?ST:REST;
+ break;
+ case ST:
+ rs_st=(dat==STBIT1)?ADDR:REST;
+ break;
+ case ADDR:
+ if (dat==RSADDR)
+ {
+ rs_st=READ;
+ len=0;
+ pch=RSADDR;
+ }
+ else
+ rs_st=DISCARD;
+ break;
+ case READ:
+ rs_rxbuf[len++]=dat;
+ pch^=dat;
+ if (dat==EDBIT0)
+ rs_st=ED;
+ if (len>=RSMAX)
+ rs_st=REST;
+ break;
+ case DISCARD:
+ if (dat==EDBIT0)
+ rs_st=DED;
+ break;
+ case DED:
+ if (dat==EDBIT1)
+ rs_st=REST;
+ else
+ rs_st=DISCARD;
+ break;
+ case ED:
+ if (dat==EDBIT1)
+ {
+ rs_st=REST;
+ --len;
+ pch^=EDBIT0;
+ if (pch==0) // Parity check passed
+ {
+ if (len<2)
+ {
+ ret=(SYSRET ^ MACTYPE);
+ SYSCALL_IRQ(RSSYSRET); // RETURN machine type
+ }
+ else
+ SYSCALL_IRQ(RSSYSBIT); // SYSCTL call happened here!!!
+ }
+ else
+ {
+ ret=(SYSRET ^ INSREP);
+ SYSCALL_IRQ(RSSYSRET); // RETURN machine type
+ }
+ }
+ else
+ {
+ rs_rxbuf[len++]=dat;
+ pch^=dat;
+ rs_st=READ;
+ if (len>=RSMAX)
+ rs_st=REST;
+ }
+ break;
+ }
+ /*//This is a repeater
+ if (IFG2&UCA0TXIFG)
+ UCA0TXBUF=dat;*/
+}
+
+void rsbus_w(int addr,unsigned char* buf,unsigned int len)
+{
+ unsigned int i;
+ if (len>4)
+ return;
+ RSOUT |= RSPIN;
+ tx_len=len+7;
+ unsigned int parity=addr^MACTYPE^RSADDR;
+ rs_tx[1]=addr;
+ for (i=0;i<len;++i)
+ parity^=(rs_tx[4+i]=buf[i]);
+ rs_tx[4+len]=parity;
+ rs_tx[5+len]=EDBIT0;
+ rs_tx[6+len]=EDBIT1;
+ tx_pos=0;
+ UCA0TXBUF=(STBIT0 & 0xff);
+ UC0IE |= UCA0TXIE;
+}
+
+/*void rsbus_w(int addr,char* buf,int len)
+{
+ // Acquire output
+ RSOUT |= RSPIN;
+ delay_ms(2);
+ unsigned int i=0;
+ unsigned int parity=addr^RSADDR;
+ // Start bits
+ while ((IFG2&UCA0TXIFG) == 0);
+ UCA0TXBUF=(STBIT0 & 0xff);
+ while ((IFG2&UCA0TXIFG) == 0);
+ UCA0TXBUF=(STBIT1 & 0xff);
+ // Addr
+ while ((IFG2&UCA0TXIFG) == 0);
+ UCA0TXBUF=(addr & 0xff);
+ // RSADDR
+ while ((IFG2&UCA0TXIFG) == 0);
+ UCA0TXBUF=(RSADDR & 0xff);
+ // Data
+ while (i<len)
+ {
+ parity^=buf[i];
+ while ((IFG2&UCA0TXIFG) == 0);
+ UCA0TXBUF=buf[i++];
+ }
+ // Parity bit
+ while ((IFG2&UCA0TXIFG) == 0);
+ UCA0TXBUF=(parity & 0xff);
+ // End bits
+ while ((IFG2&UCA0TXIFG) == 0);
+ UCA0TXBUF=(EDBIT0 & 0xff);
+ while ((IFG2&UCA0TXIFG) == 0);
+ UCA0TXBUF=(EDBIT1 & 0xff);
+ while ((IFG2&UCA0TXIFG) == 0);
+ // Release output
+ RSOUT &= ~(RSPIN);
+}*/
+
+void rsbus_syscall()
+{
+ rxhdlr(rs_rxbuf,len-1);
+}
+
+void rsbus_ret()
+{
+ rsbus_w(0,(unsigned char*)&ret,1);
+}
+
+void rsbus_init(rshdlr hdlr) // If need to change this part consult user guide pg908
+{
+ P1SEL |= BIT1 + BIT2 ; // P1.1 = RXD, P1.2=TXD
+ P1SEL2 |= BIT1 + BIT2 ; // P1.1 = RXD, P1.2=TXD
+ UCA0CTL1 |= UCSSEL_2; // UartCLK: SMCLK=4MHz
+ UCA0BR0 = 208; // BaudRate: 19200
+ UCA0BR1 = 0; // BaudRate: 19200
+ UCA0MCTL = UCBRS0 + UCBRS1; // Modulation UCBRSx = 3
+ UCA0CTL1 &= ~UCSWRST; // **Initialize USCI state machine**
+ IE2 |= UCA0RXIE; // Enable USCI_A0 RX interrupt
+ /******************* CTL for output buffer ***********************/
+ RSDIR |= RSPIN;
+ RSOUT &= ~(RSPIN); //HIGH for ENABLE -> Low as DEFAULT
+ /******************* SYSCTL INIT *************************/
+ rxhdlr=hdlr;
+ sysctl_reghdlr(RSSYSBIT,&rsbus_syscall);
+ sysctl_reghdlr(RSSYSRET,&rsbus_ret);
+}
diff --git a/rs422lib/rsbus.h b/rs422lib/rsbus.h new file mode 100644 index 0000000..036195d --- /dev/null +++ b/rs422lib/rsbus.h @@ -0,0 +1,41 @@ +/*
+ * rsbus.h
+ *
+ * Created on: 2014-4-26
+ * Author: Tuowen
+ */
+
+// DE RSOUT.RSPIN HIGH ENABLE
+// RE LOW ENABLE -> ALWAYS ENABLE
+// RECEIVE QUERY -> Conditional FNC call
+// Process -> Output (Done in main program)
+// SMCLK set to 4MHZ
+
+
+#ifndef RSBUS_H_
+#define RSBUS_H_
+
+#include<msp430g2553.h>
+#include"precomp.h"
+
+#define TYPE0 (0x00) //TYPE 0 is a dummy used for debug
+
+#define TYPE1 (0x01)
+#define TYPE2 (0x02)
+
+#define STBIT0 (0x5B)
+#define STBIT1 (0xAD)
+#define EDBIT0 (0xA4)
+#define EDBIT1 (0x52)
+
+#define TXLEN (4)
+
+#define RSMAX (20)
+
+typedef void (*rshdlr)(unsigned char*,int);
+
+void rsbus_init(rshdlr);
+
+void rsbus_w(int addr,unsigned char* buf,unsigned int len);
+
+#endif /* RSBUS_H_ */
diff --git a/rs422lib/sysctl.c b/rs422lib/sysctl.c new file mode 100644 index 0000000..fbacb9c --- /dev/null +++ b/rs422lib/sysctl.c @@ -0,0 +1,87 @@ +/*
+ * sysctl.c
+ *
+ * Created on: 2014-4-26
+ * Author: Tuowen
+ */
+
+#include<msp430g2553.h>
+#include"sysctl.h"
+
+syshdlr sysarr[8];
+
+volatile unsigned char syscall=0;
+
+void sysctl_void()
+{
+ // This is the default routine
+ // I don't want some monkey just come and call some random places in the text!!!!!
+}
+
+void sysroutine()
+{
+ if (syscall>0)
+ switch ((syscall & (-syscall)))
+ {
+ case SYS_BIT7:
+ syscall=syscall&(~SYS_BIT7);
+ sysarr[7]();
+ break;
+ case SYS_BIT6:
+ syscall=syscall&(~SYS_BIT6);
+ sysarr[6]();
+ break;
+ case SYS_BIT5:
+ syscall=syscall&(~SYS_BIT5);
+ sysarr[5]();
+ break;
+ case SYS_BIT4:
+ syscall=syscall&(~SYS_BIT4);
+ sysarr[4]();
+ break;
+ case SYS_BIT3:
+ syscall=syscall&(~SYS_BIT3);
+ sysarr[3]();
+ break;
+ case SYS_BIT2:
+ syscall=syscall&(~SYS_BIT2);
+ sysarr[2]();
+ break;
+ case SYS_BIT1:
+ syscall=syscall&(~SYS_BIT1);
+ sysarr[1]();
+ break;
+ case SYS_BIT0:
+ syscall=syscall&(~SYS_BIT0);
+ sysarr[0]();
+ break;
+ }
+ else
+ _BIS_SR(CPUOFF);
+}
+
+inline int sys_b2i(int bit)
+{
+ int i=0;
+ while (bit>1){bit>>=1;++i;}
+ return i;
+}
+
+void sysctl_reghdlr(unsigned int bit,syshdlr rot)
+{
+ bit=sys_b2i(bit);
+ sysarr[bit]=rot;
+}
+
+void sysctl_rmhdlr(unsigned int bit)
+{
+ bit=sys_b2i(bit);
+ sysarr[bit]=&sysctl_void;
+}
+
+void sysctl_init()
+{
+ unsigned int i;
+ for (i=0;i<8;++i)
+ sysarr[i]=&sysctl_void;
+}
diff --git a/rs422lib/sysctl.h b/rs422lib/sysctl.h new file mode 100644 index 0000000..11b65ed --- /dev/null +++ b/rs422lib/sysctl.h @@ -0,0 +1,38 @@ +/*
+ * sysctl.h
+ *
+ * Created on: 2014-4-26
+ * Author: Tuowen
+ */
+
+// Support 8 different syscalls
+// Possible improvement
+// CPUOFF all the time, wakeup after syscall invoked.
+
+#ifndef SYSCTL_H_
+#define SYSCTL_H_
+
+#define SYS_BIT7 (0x80)
+#define SYS_BIT6 (0x40)
+#define SYS_BIT5 (0x20)
+#define SYS_BIT4 (0x10)
+#define SYS_BIT3 (0x08)
+#define SYS_BIT2 (0x04)
+#define SYS_BIT1 (0x02)
+#define SYS_BIT0 (0x01)
+#define SYSCALL_IRQ(X) (syscall|=X,_BIC_SR_IRQ(CPUOFF))
+#define SYSCALL(X) (syscall|=X)
+
+typedef void (*syshdlr)();
+
+void sysctl_reghdlr(unsigned int bit,syshdlr rot);// Always replace
+
+void sysctl_rmhdlr(unsigned int bit);// Replace with something useless
+
+void sysroutine();
+
+void sysctl_init();
+
+extern volatile unsigned char syscall;
+
+#endif /* SYSCTL_H_ */
|