Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/Linux_HAL_Essentials/RCInput_UART/pic_firmware.asm
Views: 1799
#include <p16f690.inc>12list p=16f69034__config _INTRC_OSC_NOCLKOUT & _WDT_OFF & _PWRTE_ON & _MCLRE_OFF & _CP_OFF & _CPD_OFF & _BOR_ON & _IESO_OFF & _FCMEN_OFF56;7; This program will read until eight pwm inputs and will send its values8; through serial port at 115200bps.9;10;11; +5V -| VDD VSS |- GND12; input 6 -| RA5 RA0 |- input 113; input 5 -| RA4 RA1 |- input 214; input 4 -| RA3 RA2 |- input 315; output 4 -| RC5 RC0 |- n. c.16; output 3 -| RC4 RC1 |- status led17; output 2 -| RC3 RC2 |- output 118; n.c. -| RC6 RB4 |- input 819; n.c. -| RC7 RB5 |- rx20; tx* -| RB7 RB6 |- input 721;22;23; * In order to keep IO voltage at 3.3V use a voltage divider on TX.24;25; PS: outputs are not covered by this program yet.26;2728; The INPUT_NUM is attached to input_mask and the29; interruption. Do not change this value without30; changing the interruption and mask.31#define INPUT_NUM 832#define MAGIC 0x55AA3334cblock 0x02035; input_value, input_rise and input_mirror36; are at the bank's beginning to make easy37; the exchange of data between them.38input_value:(INPUT_NUM * 2)39input_previous40input_current41input_changed42input_mask43input_updated44sent_update45endc4647cblock 0x7248save_w49save_status50save_fsr51timer_l52timer_h53count54tmr1if_count55endc5657cblock 0x0a058; see input_value59input_rise:(INPUT_NUM * 2)60endc6162cblock 0x12063; see input_value64input_mirror:(INPUT_NUM * 2)65endc6667; Reset Vector68org 0x000069nop70nop71nop72goto Main7374; Interrupts Vector75org 0x000476; save the current context77movwf save_w78swapf STATUS, w79clrf STATUS80movwf save_status81movf FSR, w82movwf save_fsr8384; it's a input event85btfss INTCON, RABIF86goto IntInputDone8788; capture timer 189movf TMR1H, w90movwf timer_h91movf TMR1L, w92movwf timer_l93movf TMR1H, w94subwf timer_h, w95btfsc STATUS, Z96goto IntTMR1Done97movf TMR1H, w98movwf timer_h99movf TMR1L, w100movwf timer_l101IntTMR1Done:102103; capture the current input state104movf PORTA, w105btfsc PORTB, RB6106iorlw (1<<6)107btfsc PORTB, RB4108iorlw (1<<7)109110bcf INTCON, RABIF111112; identify the changed inputs113movwf input_current114xorwf input_previous, w115movwf input_changed116movf input_current, w117movwf input_previous118119; prepare for loop120movlw .1121movwf input_mask122movlw input_rise123movwf FSR124goto IntInputLoop125126IntInputNext:127incf FSR, f128129IntInputNextHalf:130; ... and ensure bank 0 selection131incf FSR, f132bsf FSR, 7133134; done if no more channels135bcf STATUS, C136rlf input_mask, f137btfsc STATUS, C138goto IntInputDone139140IntInputLoop:141; skip if channel not changed142movf input_mask, w143andwf input_changed, w144btfsc STATUS, Z145goto IntInputNext146147; check if it is raising or falling148andwf input_current, w149btfss STATUS, Z150goto IntInputRise151152; calculate and move the lsb to input_value153movf INDF, w154subwf timer_l, w155bcf FSR, 7156movwf INDF157158; calculate and move the msb to input_value159bsf FSR, 7160incf FSR, f161movf INDF, w162btfss STATUS, C163incf INDF, w164subwf timer_h, w165bcf FSR, 7166movwf INDF167168goto IntInputNextHalf169170IntInputRise:171; tell main loop we have all channels172btfsc input_mask, 1173incf input_updated, f174175; save the rise instant176movf timer_l, w177movwf INDF178incf FSR, f179movf timer_h, w180movwf INDF181goto IntInputNextHalf182183IntInputDone:184185; restore the previous context186movf save_fsr, w187movwf FSR188swapf save_status, w189movwf STATUS190swapf save_w, f191swapf save_w, w192retfie193194Main:195; bank 0196clrf STATUS197198clrf PORTA199clrf PORTB200clrf PORTC201202; bank 1203bsf STATUS, RP0204205movlw (b'111'<<IRCF0)206movwf OSCCON ; set internal oscillator frequency to 8 MHz207208movlw (0<<NOT_RABPU)209movwf OPTION_REG210211; ,------ input 6212; |,----- input 5213; ||,---- input 4214; |||,--- input 3215; ||||,-- input 2216; |||||,- input 1217movlw b'11111111'218movwf TRISA ; set PORTA as input219movwf WPUA ; enable weak pull-up220movwf IOCA ; enable interrupt-on-change221222; ,-------- tx223; |,------- input 6224; ||,------ rx225; |||,----- input 7226movlw b'01111111'227movwf TRISB228229; ,------ output 4230; |,----- output 3231; ||,---- output 2232; |||,--- output 1233; ||||,-- status234; |||||,- n. c.235movlw b'11000001'236movwf TRISC237238movlw (1<<TXEN|1<<BRGH)239movwf TXSTA ; enable async transmitter and select high baud rate240241movlw (1<<BRG16)242movwf BAUDCTL ; 16-bit baud rate generator243244movlw .16 ; use value 16 for SPBRG:SPBRGH to get 115200bps baud rate245movwf SPBRG246clrf SPBRGH247248; Bank 2249bcf STATUS, RP0250bsf STATUS, RP1251252clrf ANSEL253clrf ANSELH254255; ,------- input 6256; | ,----- input 7257movlw b'01010000'258movwf WPUB259movwf IOCB260261; bank 0262clrf STATUS263264; clear the first two banks265movlw 0x020266call ClearBank267movlw 0x0A0268call ClearBank269270movlw (1<<SPEN|1<<CREN)271movwf RCSTA272273movlw (1<<T1CKPS0|1<<TMR1ON)274movwf T1CON ; enable timer and set frequency to 1MHz (=8Mhz/4/2)275276movlw (1<<GIE|1<<PEIE|1<<RABIE)277movwf INTCON278279MainLoopNoUpdate:280; toggle status led if idle for more than INPUT_NUM * 2000 usec281movf timer_h, w282subwf TMR1H, w283sublw high(.2000 * INPUT_NUM)284btfsc STATUS, C285goto MainLoop286; toggle status led at each 8 timer1 overflows, i.e., about 0.52 sec287btfss PIR1, TMR1IF288goto MainLoop289bcf PIR1, TMR1IF290incf tmr1if_count, f291movlw H'07'292andwf tmr1if_count, w293btfss STATUS, Z294goto MainLoop295; toggle status led296movf PORTC, w297xorlw (1<<RC1)298movwf PORTC299MainLoop:300; loop if no updates301movf sent_update, w302subwf input_updated, w303btfsc STATUS, Z304goto MainLoopNoUpdate305306; prepare for mirroring307addwf sent_update, f308movlw (INPUT_NUM * 2)309movwf count310movlw input_value311movwf FSR312313MirrorLoop:314movf INDF, w315bsf STATUS, IRP316movwf INDF317bcf STATUS, IRP318incf FSR, f319decfsz count, f320goto MirrorLoop321322; restart if there was update while mirroring323movf input_updated, w324subwf sent_update, w325btfss STATUS, Z326goto MainLoop327328; finally send the captured values329; send a magic number to sync330movlw low(MAGIC)331call Send332movlw high(MAGIC)333call Send334335; prepare for send loop336movlw (INPUT_NUM * 2)337movwf count338movlw low(input_mirror)339bsf STATUS, IRP340movwf FSR341342SendLoop:343movf INDF, w344call Send345incf FSR, f346decfsz count, f347goto SendLoop348349bcf STATUS, IRP350351; set led on352bcf PORTC, RC1353354goto MainLoop355356Send:357btfss PIR1, TXIF358goto $ - 1359movwf TXREG360return361362ClearBank:363; clears the gpr bank pointed by w plus irp,364; but preserves the common 16 bytes.365366; ensure the beginning of the bank367andlw b'10100000'368movwf FSR369movlw .80370movwf count371372ClearBankLoop:373clrf INDF374incf FSR, f375decfsz count, f376goto ClearBankLoop377return378379end380381382383