2
1

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?

PIC18F27Q43 外部ピン割込み Interrupt On Change

Last updated at Posted at 2024-05-20

Q43の外部スイッチ割込み 

IMG_4691.JPG

外部のスイッチで、割込みを発生させる設定方法です。

1.割込みピンの割り付け可能ポート

availability per Device.png

18F27Q43は、28ピンなので、PORTA、PORTB、PORTCに割り付けることができます。

2.Interrupt On Change Block Diaglam

IOCdiaglam.png

2-1.モジュールを有効にする。IOCIEビットをセット。これで、個別割込みが許可されます。

Q_Peripheral.c
    PIE0bits.IOCIE=1;//IOC割込み許可
    PIR0bits.IOCIF=0;//IOC割込みフラグ

2-2.個別の割込みピン設定
立ち上がり検出:IOCxPレジスタ
IOCxP.png
ex.)RA3ピンを立ち上がり割込みピンとして指定。

IOCAPbits.IOCAP3 = 1; //RA3 立ち上がりIOC割込みピン設定

立ち下がり検出:IOCxNレジスタ
IOCxN.png
ex.)RC0ピンを立ち下がり割込みピンとして指定。

IOCCNbits.IOCCN0 = 1; //RC0 立下りIOC割込みピン設定

2-3.個別の割込みフラグの処理
割り込み処理関数実行中に、検出された状態変化のビットデータが失われないように、XORとANDを組み合わせて、取りこぼしを防止しながら、該当ビットをクリアして、関数を終了させます。

XOR 0 1
0 0 1
1 1 0

ex)RC0割込みが発生し、処理が終わって割り込みフラグをクリアする方法
取りこぼし防止.jpg

関数の最初で、XORで、実行先頭の状態を保持し、処理がおわり、該当フラグをクリアするとき、割り込み実行中の状態変化をANDで、取り込んでいます。

4.IOC割込みコード

Q_Peripheral.h

#ifndef Q_PERIPHERAL27Q43_H
#define	Q_PERIPHERAL27Q43_H

#ifdef	__cplusplus
extern "C" {
#endif

#include <xc.h>
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include <stdbool.h>
    
#define Low 0
#define High 1
   
#define _XTAL_FREQ 32000000
#define BAUDRATE 115200
#define SET_SPBRG_DATA  (((unsigned int)((_XTAL_FREQ/4)/BAUDRATE))-1)
#define SET_SPBRG_DATA1 (((unsigned int)((_XTAL_FREQ/16)/BAUDRATE))-1)   
//USART---------------------------------------
#define RXUSART_BUFFER_SIZE 20
typedef struct
{
    uint8_t buf[RXUSART_BUFFER_SIZE];
    uint8_t length;
    uint8_t completed;
}_rxUsart;
extern _rxUsart rxUsart;
extern void usartInit(void);
extern void putch(uint8_t);
extern uint8_t getch(void);
//Timer--------------------------------------
typedef struct
{
    uint16_t cnt;
    bool fg;
}_tm;
extern _tm tm0,tm2;
extern void timer0Init(void);    
extern void timer2Init(void);
//IOC------------------------------------------
extern void iocInit(void);
typedef struct
{
    bool fg;
}_ioc;
extern _ioc ioc;  

#ifdef	__cplusplus
}
#endif

#endif	/* Q_PERIPHERAL27Q43_H */


Q_Peripheral.c

#include <pic18f27q43.h>
#include "Q_peripheral27Q43.h"

//*****************************************************//
//Timer0初期化
//*****************************************************//
_rxUsart rxUsart;
void usartInit(void)
{
    //1.ボーレート設定115200
    U1BRG=SET_SPBRG_DATA1;
    //2.モード 非同期
    U1CON0bits.MODE=0b0000; //Asynchronous 8-bit USART mode
    //4.Serial port enabled
    U1CON1bits.ON=1;
    //5.Transmit is enabled.
    U1CON0bits.TXEN=1;
    U1CON0bits.RXEN=1;
    //6.PPS
    PPSLOCK = 0x55; 
    PPSLOCK = 0xAA;
    PPSLOCKbits.PPSLOCKED = 0;//Unlock.
    U1RXPPS=0b010111;//RC7:rx
    RC6PPS=0x20;//RC6:tx
    TRISC|=0x80;
    PPSLOCK = 0x55; 
    PPSLOCK = 0xAA;
    PPSLOCKbits.PPSLOCKED = 1;//lock.
    //7.interrupt
    PIR4bits.U1RXIF=0;
    PIE4bits.U1RXIE=1; 
}

void putch(uint8_t _txData)
{
    if(U1ERRIRbits.TXMTIF==High)//シフトレジスタ空?
    {
        do{
            U1TXB=_txData;
            while(U1ERRIRbits.TXMTIF==Low);
        }while(U1FIFObits.TXBF);//TXバッファ空になるまで送信。
    }else{
        //error operation
    }
}

uint8_t getch(void)
{
    while(PIR4bits.U1RXIF==Low);//受信完了
    return U1RXB;
}

//*****************************************************//
//Timer0初期化
//*****************************************************//
_tm tm0;
void timer0Init(void)
{
//Timer0初期化--------------------------------------------------
    T0CON1bits.CS=0b010;//クロックソースFosc/4
    T0CON1bits.CKPS=0b0011;//プリスケ1:8
    T0CON0bits.MD16=1;//16bitsタイマー
    T0CON0bits.OUTPS=0b0000;//ポストスケーラ1:1
    TMR0H=0xD8;//10ms Fosc=32Mhz
    TMR0L=0xF0;//10ms 
    T0CON0bits.EN=1;
    PIE3bits.TMR0IE=1;
    PIR3bits.TMR0IF=0;
}

//*****************************************************//
//IOC Interrupt On Change 初期化
//*****************************************************//
_ioc ioc;
void iocInit(void)
{
    IOCCNbits.IOCCN0=1;//RC0:立下り検出設定
    TRISC|=0x01;       //RC0:入力ピン
    PIE0bits.IOCIE=1; //外部割込み許可
    PIR0bits.IOCIF=0;  //外部割込みフラグクリア
}

Q_interrupt.h
#ifndef Q_INTERRUPT_H
#define	Q_INTERRUPT_H

#ifdef	__cplusplus
extern "C" {
#endif

#include <xc.h>
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include <stdbool.h>
#include "Q_peripheral27Q43.h"
  
extern void __interrupt(irq(IRQ_U1RX)) USART1RX_ISR(void);    
extern void __interrupt(irq(IRQ_TMR0)) Timer0_ISR(void); 
extern extern void __interrupt(irq(IRQ_TMR2)) Timer2_ISR(void); 
extern void __interrupt(irq(IRQ_IOC)) IOC_ISR(void);

#ifdef	__cplusplus
}
#endif

#endif	/* Q_INTERRUPT_H */
#include "Q_interrupt27Q43.h"

//****************割り込み関数***********************//
// USART1割込み
//**************************************************//
void __interrupt(irq(IRQ_U1RX)) USART1RX_ISR(void)
{
    uint8_t ch;
    PIR4bits.U1RXIF=0;
    ch=getch();
    rxUsart.buf[rxUsart.length++]=ch;
    if(rxUsart.length>RXUSART_BUFFER_SIZE)
    {
        rxUsart.length=0;
    }
    if(ch==0x0a)
    {
        rxUsart.buf[rxUsart.length-2]=0x00;
        PIE4bits.U1RXIE=0;
        rxUsart.completed=1;
    }
}

//****************割り込み関数***********************//
// Timer0割込み
//**************************************************//
void __interrupt(irq(IRQ_TMR0)) Timer0_ISR(void)
{
    PIR3bits.TMR0IF=0;
    tm0.cnt++;
    if(tm0.cnt==50)
    {
        tm0.cnt=0;
        tm0.fg=true;
        T0CON0bits.EN=0;
        PIE3bits.TMR0IE=0;
    }
    
    TMR0L=0xF0;//10ms
}

//****************割り込み関数***********************//
// IOC割込み
// ※印は、割り込み関数実行中の変化を取りこぼさないためのコード。
//**************************************************//
void __interrupt(irq(IRQ_IOC)) IOC_ISR(void)
{
    uint8_t val,mask;
    
    PIR0bits.IOCIF=0;
    val=IOCCF;  //※IOCフラグレジスタ読み出し
    mask=0xFF;  //※ゼロクリアマスク
    mask=mask^val;//※現状を記録
    if(IOCCNbits.IOCCN0==1 && val==0x01)
    {
        ioc.fg=true; //main関数で実処理開始
        PIE0bits.IOCIE=0;//一時割り込み停止
    }
    //zero clear--------------    
    IOCCF&=mask;   //※状態変化の取りこぼしをしない。
}


main.c
// PIC18F27Q43 Configuration Bit Settings

// 'C' source line config statements

// CONFIG1
#pragma config FEXTOSC = OFF    // External Oscillator Selection (Oscillator not enabled)
#pragma config RSTOSC = HFINTOSC_64MHZ// Reset Oscillator Selection (HFINTOSC with HFFRQ = 64 MHz and CDIV = 1:1)

// CONFIG2
#pragma config CLKOUTEN = OFF   // Clock out Enable bit (CLKOUT function is disabled)
#pragma config PR1WAY = OFF     // PRLOCKED One-Way Set Enable bit (PRLOCKED bit can be set and cleared repeatedly)
#pragma config CSWEN = ON       // Clock Switch Enable bit (Writing to NOSC and NDIV is allowed)
#pragma config FCMEN = OFF      // Fail-Safe Clock Monitor Enable bit (Fail-Safe Clock Monitor disabled)

// CONFIG3
#pragma config MCLRE = EXTMCLR  // MCLR Enable bit (If LVP = 0, MCLR pin is MCLR; If LVP = 1, RE3 pin function is MCLR )
#pragma config PWRTS = PWRT_OFF // Power-up timer selection bits (PWRT is disabled)
#pragma config MVECEN = ON      // Multi-vector enable bit (Multi-vector enabled, Vector table used for interrupts)
#pragma config IVT1WAY = ON     // IVTLOCK bit One-way set enable bit (IVTLOCKED bit can be cleared and set only once)
#pragma config LPBOREN = OFF    // Low Power BOR Enable bit (Low-Power BOR disabled)
#pragma config BOREN = SBORDIS  // Brown-out Reset Enable bits (Brown-out Reset enabled , SBOREN bit is ignored)

// CONFIG4
#pragma config BORV = VBOR_1P9  // Brown-out Reset Voltage Selection bits (Brown-out Reset Voltage (VBOR) set to 1.9V)
#pragma config ZCD = OFF        // ZCD Disable bit (ZCD module is disabled. ZCD can be enabled by setting the ZCDSEN bit of ZCDCON)
#pragma config PPS1WAY = OFF     // PPSLOCK bit One-Way Set Enable bit (PPSLOCKED bit can be cleared and set only once; PPS registers remain locked after one clear/set cycle)
#pragma config STVREN = ON      // Stack Full/Underflow Reset Enable bit (Stack full/underflow will cause Reset)
#pragma config LVP = ON         // Low Voltage Programming Enable bit (Low voltage programming enabled. MCLR/VPP pin function is MCLR. MCLRE configuration bit is ignored)
#pragma config XINST = OFF      // Extended Instruction Set Enable bit (Extended Instruction Set and Indexed Addressing Mode disabled)

// CONFIG5
#pragma config WDTCPS = WDTCPS_31// WDT Period selection bits (Divider ratio 1:65536; software control of WDTPS)
#pragma config WDTE = OFF       // WDT operating mode (WDT Disabled; SWDTEN is ignored)

// CONFIG6
#pragma config WDTCWS = WDTCWS_7// WDT Window Select bits (window always open (100%); software control; keyed access not required)
#pragma config WDTCCS = SC      // WDT input clock selector (Software Control)

// CONFIG7
#pragma config BBSIZE = BBSIZE_512// Boot Block Size selection bits (Boot Block size is 512 words)
#pragma config BBEN = OFF       // Boot Block enable bit (Boot block disabled)
#pragma config SAFEN = OFF      // Storage Area Flash enable bit (SAF disabled)
#pragma config DEBUG = OFF      // Background Debugger (Background Debugger disabled)

// CONFIG8
#pragma config WRTB = OFF       // Boot Block Write Protection bit (Boot Block not Write protected)
#pragma config WRTC = OFF       // Configuration Register Write Protection bit (Configuration registers not Write protected)
#pragma config WRTD = OFF       // Data EEPROM Write Protection bit (Data EEPROM not Write protected)
#pragma config WRTSAF = OFF     // SAF Write protection bit (SAF not Write Protected)
#pragma config WRTAPP = OFF     // Application Block write protection bit (Application Block not write protected)

// CONFIG10
#pragma config CP = OFF         // PFM and Data EEPROM Code Protection bit (PFM and Data EEPROM code protection disabled)

// #pragma config statements should precede project file includes.
// Use project enums instead of #define for ON and OFF.

#include <xc.h>
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include <stdbool.h>
#include "Q_peripheral27Q43.h"
#include "Q_interrupt27Q43.h"
#include "Q_initialize.h"
#include "Q_I2C1.h"
#include "I2C_LCD.h"
#include "stringFormat.h"

void portInit(void);
void oscillatorInit(void);
void vicInit(void);

void main(void)
{
    uint8_t counter=0;
    //CPUハード初期化-----------------------
    portInit();
    oscillatorInit();
    vicInit();
    
    //周辺機能初期化--------------------------------
    timer0Init();
    iocInit();
    usartInit();
    printf("START Interrupt On Change\n");    
    I2C1_Init();    
    INTCON0bits.GIE=1;//Enable all masked interrupts
    
    while(1)
    {
        //Timer0 interrupt-------
        if(tm0.fg)
        {
            tm0.fg=false;
            PORTBbits.RB0=~PORTBbits.RB0;
            T0CON0bits.EN=1;
            PIE3bits.TMR0IE=1;
        } 
        
        //Interrupt On Change Interrupt--------
        if(ioc.fg)
        {
            ioc.fg=false;
            printf("Switch ON:%d\n",counter);
            PORTBbits.RB1=~PORTBbits.RB1;
            counter++;
            PIE0bits.IOCIE=1;
        }
    }
    return;
}

void oscillatorInit(void)
{
    //オシレータ設定----------------
    OSCCON3bits.CSWHOLD=1;//Hold
    OSCCON1bits.NDIV=1;//64Mhz/2=32Mhz;
    while(!OSCCON3bits.NOSCR);
    while(!PIR0bits.CSWIF);//ready state
    PIR0bits.CSWIF=0;
    OSCCON3bits.CSWHOLD=0;
    while(!OSCCON3bits.ORDY);
}

void portInit(void)
{
    //ポート設定----------------------    
    PORTA=0x00;
    LATA=0x00;
    ANSELA=0x00;
    TRISA=0x00;
    
    PORTB=0x00;
    LATB=0x00;
    ANSELB=0x00;
    TRISB=0x00;
    
    PORTC=0x00;
    LATC=0x00;
    ANSELC=0x00;
    TRISC=0x00;
}

void vicInit(void)
{
 //割り込みテーブルaddress設定----------------------------------
    INTCON0bits.GIE=0;//Enable all masked interrupts
    IVTLOCK=0x55;
    IVTLOCK=0xAA;
    IVTLOCKbits.IVTLOCKED=0;
    IVTBASE = 0x000008;
    IVTLOCK=0x55;
    IVTLOCK=0xAA;
    IVTLOCKbits.IVTLOCKED=1;
}
2
1
0

Register as a new user and use Qiita more conveniently

  1. You get articles that match your needs
  2. You can efficiently read back useful information
  3. You can use dark theme
What you can do with signing up
2
1

Delete article

Deleted articles cannot be recovered.

Draft of this article would be also deleted.

Are you sure you want to delete this article?