nobcha23の日記

PICマイコンやArduinoを使う電子回路遊びを紹介します

Si5351aのクロック発生器ができる I made up clock generator of Si5351a.

元々はエアバンド用の局発用に使おうと始めたものです。


1MHzから200MHzまでのクロック発生器が何とかできました。


Mainのほかに使う関数はlcd.c:4ビットデータ接続で1602型の液晶をつないで使うmemory.c:MPLABXで生成するEEPROM用ドライバー、si5351a.c:TJ LABから引用したsi5351a用ドライバー、です。



まずはmain.cです。

I had started this project for local oscillator of air band receiver.

I had made up clock generator from 1MHz to 200MHz.

The software is combined main.c, lcd.c:4bits parallel LCD driver, memory.c: EPROM driver generated by MPLABX, and si5351a.c: si5351a driver coming from Tj lab.

Please refer main.c below.

/********Si5351a clock generator*******************
PIC16F1829SW MSSP2 i2c 
 * 01/12/2018 TRIS Normal:output, ack check input

*********** Si5351a*****************
Bit handling RB5:SDA2, RB7:SCL2
 * 05/06/2018 i2c scan OK! "C0" stop.
 * 05/06/2018 Si5351a Freq set OK 10MHz
 * 05/06/2018 Start up ?? EPROM recover
 * 05/11/2018 variable name change

*********** SW *******************
ROTARY1:RA5, ROTARY2:RA4
SW3(Freq_step):RC7,  SW2(Memo_write):RB4 SW1:MCR,RA3
LED/RB6

*********** LCD4 bit *******************
 LCDRS:RA0, EN:RA1
 LCDdata D4:RC2, D5:RC3, D6:RC4, D7:RC5

*********** Config *********************
16MHzXtal:HS,WDTE_OFF,PWRTE_OFF,MCLRE_OFF
CP_OFF,CPD_OFF,BOREN_OFF,CLKOUTEN_ON
IESO_OFF,FCMEN_OFF
 * 21 nov 2017 display ok
 * 01 Jan 2018 Si5351a convert
 * 06 Jan 2018 i2c scan OK Uebo FUNC trip
 * 07 Jan 2018 Si5351a 10MHz settei NG
 * 14 Jan 2018 set_freq argument NG?
 * 06 May 2018 rotary OK eeprom ok 5351a OK mssp2 no use
 * 06 May 2018 restart sw2 need
*/

#define _XTAL_FREQ 16000000
#define PIC_CLOCK  16000000

#define SW_Rotary1 PORTAbits.RA5   /RA5
#define SW_Rotary2 PORTAbits.RA4   /RA4
#define SW3 PORTCbits.RC7          /RC7
#define SW2 PORTBbits.RB4          /RB4
        //SW1:MCR,RA3
#define HEART_BEAT LATBbits.RB6    /RB6

#include <xc.h>
#include <htc.h>
#include <stdio.h>
#include "lcd.h"
#include "si5351_set.h"
#include "memory.h"

// CONFIG1
#pragma config FOSC = INTOSC    // Oscillator Selection INT: device clock supplied to CLKIN pin)
#pragma config WDTE = OFF       // Watchdog Timer Enable (WDT disabled)
#pragma config PWRTE = OFF      // Power-up Timer Enable (PWRT disabled)
#pragma config MCLRE = ON       // MCLR Pin Function Select (MCLR/VPP pin function is RA3)
#pragma config CP = OFF         // Flash Program Memory Code Protection (Program memory code protection is disabled)
#pragma config CPD = OFF        // Data Memory Code Protection (Data memory code protection is disabled)
#pragma config BOREN = OFF      // Brown-out Reset Enable (Brown-out Reset disabled)
#pragma config CLKOUTEN = OFF   // Clock Out Enable (CLKOUT function is disabled. I/O or oscillator function on the CLKOUT pin)
#pragma config IESO = OFF       // Internal/External Switchover (Internal/External Switchover mode is disabled)
#pragma config FCMEN = OFF      // Fail-Safe Clock Monitor Enable (Fail-Safe Clock Monitor is enabled)

// CONFIG2
#pragma config WRT = OFF        // Flash Memory Self-Write Protection (Write protection off)
#pragma config PLLEN = OFF      // PLL Enable (4x PLL disabled)
#pragma config STVREN = ON      // Stack Overflow/Underflow Reset Enable (Stack Overflow or Underflow will cause a Reset)
#pragma config BORV = LO        // Brown-out Reset Voltage Selection (Brown-out Reset Voltage (Vbor), low trip point selected.)
#pragma config LVP = OFF        // Low-Voltage Programming Enable (High-voltage on MCLR/VPP must be used for programming)

// valiables
long freq, freq_0;              // freq:set frequency
long fstep;                     // fstep
int  n1[42], ra, rb, ra_n, rb_n, r_be, j, k;
char fdds[12];                  //DSP

// function prototyped
void Step_Set();               // step 100-10,000,000
void Dsp_Disp();               // 
void Step_Disp();              // step
void Eeprom_Write_Long(unsigned int,long);
long int Eeprom_Read_Long(unsigned int);
void Fdds_Space ( char*);
void LongToStr( long, char*);
void monit(long, long);

void main(){
//********* PORT *********
    OSCCON = 0b01111000;   //INTOSC 16MHz

    TRISA = 0b00111100;    //PORTA RA5,4:Rotary, RA3:SW1;MCR RA2:CKi
    TRISB = 0b00010000;    //PORTB  RB4:SW2 1:INPUT
    TRISC = 0b10000011;    //PORTC R7:SW3

    LATA = 0b00111100;     //PORTA
    LATB = 0b10110000;     //PORTB
    LATC = 0b00000000;     //PORTC

    ANSELA=0;              //PORTA,B,C all digital
    ANSELB=0;
    ANSELC=0;
    CM1CON0 = 0b00000111;  // Nousing compalator
    CM2CON0 = 0b00000111;  // Nousing compalator
    
    OPTION_REG = 0b10100100; // INTEDG,T0CS,T0CKI 1,T0SE0,PSA

//CCP4 PWM initializing (83.8KHz on RB3 @16MHz)
    CCP4CON = 0b00001111;  // use PWM mode
    CCPR4L = 0x0c; 	       // duty is 50%
    CCPTMRS = 0;	       // Select TMR2
//  TMR2 initilizing
    T2CON = 0b00000100;	   // POSTSCALE 1:1 ,TMR2 ON , PRESCALE 1:1
    PR2 = 0x17; 	       // resolution is 6.5bit mode
    TMR2ON = 1;		       // TMR2 start

//********* LCD *********
    lcd_init();
    lcd_goto(0);
    lcd_puts("Si5351a CLOCK"); //LCD
    lcd_goto(0x40);            // 2nd line
    lcd_puts("generator");     //LCD
    __delay_ms(1000);          //Pb(=1000)
    lcd_clear();

    si5351_init();             // 10MHz set

// RB6 monit LED on_off
//
    monit(500,200);

    freq=Eeprom_Read_Long(0);   // EPROMdata recover
    set_freq(freq);
    fstep=Eeprom_Read_Long(1);  //  fstep data from EEPROM Read
   
    Dsp_Disp();                 // set adseton Si5351a
    freq_0=freq;
 // RB6 monit LED on_off
    monit(1000,500);
 // RB6 monit LED on_off
    monit(1000,1000);
    
    if(freq<1000000 || freq>200000000){ //1-200MHz
        freq = 10000000;
        lcd_goto(0x40);                 // 2nd line
        lcd_puts("Feq Read Error");     //LCD
        __delay_ms(2000);
        lcd_clear();
    }
    if(fstep==100 || fstep==1000 || fstep==10000 || fstep==100000 || fstep==1000000 || fstep==10000000)
    {

    __delay_ms(10);
    }
        else{
           fstep=100;
           lcd_goto(0x40);                // 2nd line
           lcd_puts("Step Read Error");   //LCD
           __delay_ms(2000);
           lcd_clear();
         }


//    while(SW2 == 1){                    // wait on SW2
////       Step_Disp();                   //  stepdata displaying
// RB6 monit LED on_off
//       monit(1000,500);
//    }

    Dsp_Disp();
    Step_Disp();

    set_freq(freq);

// RB6 
    PORTBbits.RB6 = k++ & 0x1;   // Mon Led on;
    while(1){
        if( SW3 == 0){           //
             Step_Set();
            }

        if( SW2 == 0){           //
            lcd_goto(0x4E);
            lcd_putch(0x2F);      //
            Eeprom_Write_Long(0, freq);
            Eeprom_Write_Long(1, fstep);
            __delay_ms(300);
            lcd_goto(0x4E);
            lcd_putch(0x20);       //
        }

     // RA4/RA5 Rotary encoder
        ra = SW_Rotary2;     //PORTAbits.RA4  
        rb = SW_Rotary1;     //PORTAbits.RA5  
        __delay_ms(4);

        ra_n = SW_Rotary2;   //PORTAbits.RA4 5mS
        rb_n = SW_Rotary1;   //PORTAbits.RA5 5mS
        __delay_ms(1);
//********* Increase or decrease? *********
        if(ra_n != ra || rb_n != rb){
            ra_n = ra_n * 2 + rb_n;
            ra = ra * 2 + rb;
            r_be = (ra<<1) ^ ra_n;
            r_be = r_be & 3;
            freq_0 = freq;
            if(ra==0 && rb==0){
                if(r_be >= 2){             // increase
                    freq = freq + fstep;
                    if(freq > 200000000){  // Max 200MHz
                        freq = freq_0;
                    }
                }
                else{                      //
                    freq = freq - fstep;
                    if(freq < 1000000){    // 1MHz
                        freq = freq_0;
                    }
                }

                set_freq(freq);
                Dsp_Disp();

// RB6 LED on/off in turn
                PORTBbits.RB6 = j++ & 0x1;   // Mon Led on;
            }
        }
    }
}

//**** Write LONG value onto EEPROM ****
void Eeprom_Write_Long(unsigned int adr, long dat){
    int i;
    for(i = 0; i < 4; i++) {
        DATAEE_WriteByte(adr * 4 + i, (unsigned short)((dat >> i * 8) & 0x00ff));
    }
}

//**** Read LONG value from EEPROM ****
long int Eeprom_Read_Long(unsigned int adr) {
    int i;
    long dat;
     for(i = 1; i < 5; i++) {
         dat = (dat << 8) + DATAEE_ReadByte((adr + 1)* 4 - i);
     }
        return dat;
}

//*********step selection*********
// 100-10000000
void Step_Set()
{
    fstep = fstep*10;
    if (fstep > 10000000) { fstep=100;}
    Step_Disp();
}

//********* fstep*********
void Step_Disp()                   // fstep/LCD
{
    if (fstep == 100){
        lcd_goto(0x44);
        lcd_puts("Step 100Hz  ");   //LCD step
    }
    else if (fstep == 1000){
        lcd_goto(0x44);
        lcd_puts("Step 1kHz   ");
    }
    else if (fstep == 10000){
        lcd_goto(0x44);
        lcd_puts("Step 10KHz  ");
    }
    else if (fstep == 100000){
        lcd_goto(0x44);
        lcd_puts("Step 100KHz ");
    }
    else if (fstep == 1000000){
        lcd_goto(0x44);
        lcd_puts("Step 1MHz   ");
    }
    else {
        lcd_goto(0x44);
        lcd_puts("Step 10MHz  ");
    }
    __delay_ms(200);

}

//*********display *********
void Dsp_Disp()                //
{
    char fdds1[16];
    const unsigned char fdds2[] = "test";
    LongToStr(freq, fdds);     // Long data
    Fdds_Space(fdds);          //

    if (freq >= 1000000) {
        fdds1[14] = '\0';
        fdds1[13] = 'z';
        fdds1[12] = 'H';
        fdds1[11] = fdds[10];
        fdds1[10] = fdds[9];
        fdds1[9] = fdds[8];
        fdds1[8] = ',';
        fdds1[7] = fdds[7];
        fdds1[6] = fdds[6];
        fdds1[5] = fdds[5];
        fdds1[4] = ',';
        fdds1[3] = fdds[4];
        fdds1[2] = fdds[3];
        fdds1[1] = fdds[2];
        fdds1[0] =  ' ';
    } else if (freq>= 1000) {
        fdds1[14] = '\0';
        fdds1[13] = 'z';
        fdds1[12] = 'H';
        fdds1[11] = fdds[10];
        fdds1[10] = fdds[9];
        fdds1[9] = fdds[8];
        fdds1[8] = ',';
        fdds1[7] = fdds[7];
        fdds1[6] = fdds[6];
        fdds1[5] = fdds[5];
        fdds1[4] = ' ';
        fdds1[3] = ' ';
        fdds1[2] = ' ';
        fdds1[1] = ' ';
        fdds1[0] = ' ';
    } else {
        fdds1[14] = '\0';
        fdds1[13] = 'z';
        fdds1[12] = 'H';
        fdds1[11] = fdds[10];
        fdds1[10] = fdds[9];
        fdds1[9] = fdds[8];
        fdds1[8] = ' ';
        fdds1[7] = ' ';
        fdds1[6] = ' ';
        fdds1[5] = ' ';
        fdds1[4] = ' ';
        fdds1[3] = ' ';
        fdds1[2] = ' ';
        fdds1[1] = ' ';
        fdds1[0] = ' ';
    }
    lcd_goto(0);
    lcd_puts(fdds1);      //LCD
}

void LongToStr(long dat, char *fm){
    long fmdat;
    int i;
    fmdat = dat;
    for (i=0; i<11; i++){
        fm[10-i] =( fmdat % 10 ) | 0x30;
        fmdat = fmdat / 10;
    }
}

void  Fdds_Space(char *fm){
    int i;
    for (i=0; i<11; i++){
        if( fm[i] == 0x30){
            fm[i]=0x20;
        }
        else i=11;
    }
}

/***************************************
* Converting 2/4 hex to ASCII
****************************************/
void monit(long on_time, long off_time){
// RB6 monit LED on_off
//
       PORTBbits.RB6=1;       // Mon Led on
       __delay_ms(on_time);
       PORTBbits.RB6=0;
       __delay_ms(off_time);
}

Memory.cです。

/**
  MEMORY Generated Driver File

  @Company
    Microchip Technology Inc.

  @File Name
    memory.c

  @Summary
    This is the generated driver implementation file for the MEMORY driver using MPLAB? Code Configurator

  @Description
    This source file provides implementations of driver APIs for MEMORY.
    Generation Information :
        Product Revision  :  MPLAB? Code Configurator - v2.25.2
        Device            :  PIC16F1829
        Driver Version    :  2.00
    The generated drivers are tested against the following:
        Compiler          :  XC8 v1.34
        MPLAB             :  MPLAB X v2.35 or v3.00
*/

/*
Copyright (c) 2013 - 2015 released Microchip Technology Inc.  All rights reserved.

Microchip licenses to you the right to use, modify, copy and distribute
Software only when embedded on a Microchip microcontroller or digital signal
controller that is integrated into your product or third party product
(pursuant to the sublicense terms in the accompanying license agreement).

You should refer to the license agreement accompanying this Software for
additional information regarding your rights and obligations.

SOFTWARE AND DOCUMENTATION ARE PROVIDED "AS IS" WITHOUT WARRANTY OF ANY KIND,
EITHER EXPRESS OR IMPLIED, INCLUDING WITHOUT LIMITATION, ANY WARRANTY OF
MERCHANTABILITY, TITLE, NON-INFRINGEMENT AND FITNESS FOR A PARTICULAR PURPOSE.
IN NO EVENT SHALL MICROCHIP OR ITS LICENSORS BE LIABLE OR OBLIGATED UNDER
CONTRACT, NEGLIGENCE, STRICT LIABILITY, CONTRIBUTION, BREACH OF WARRANTY, OR
OTHER LEGAL EQUITABLE THEORY ANY DIRECT OR INDIRECT DAMAGES OR EXPENSES
INCLUDING BUT NOT LIMITED TO ANY INCIDENTAL, SPECIAL, INDIRECT, PUNITIVE OR
CONSEQUENTIAL DAMAGES, LOST PROFITS OR LOST DATA, COST OF PROCUREMENT OF
SUBSTITUTE GOODS, TECHNOLOGY, SERVICES, OR ANY CLAIMS BY THIRD PARTIES
(INCLUDING BUT NOT LIMITED TO ANY DEFENSE THEREOF), OR OTHER SIMILAR COSTS.
*/

/**
  Section: Included Files
*/

#include <xc.h>
#include "memory.h"

/**
  Section: Flash Module APIs
*/

uint16_t FLASH_ReadWord(uint16_t flashAddr)
{
    uint8_t GIEBitValue = INTCONbits.GIE;   // Save interrupt enable

    INTCONbits.GIE = 0;     // Disable interrupts
    EEADRL = (flashAddr & 0x00FF);
    EEADRH = ((flashAddr & 0xFF00) >> 8);

    EECON1bits.CFGS = 0;    // Deselect Configuration space
    EECON1bits.EEPGD = 1;   // Select Program Memory
    EECON1bits.RD = 1;      // Initiate Read
    NOP();
    NOP();
    INTCONbits.GIE = GIEBitValue;   // Restore interrupt enable

    return ((EEDATH << 8) | EEDATL);
}

void FLASH_WriteWord(uint16_t flashAddr, uint16_t *ramBuf, uint16_t word)
{
    uint16_t blockStartAddr = (uint16_t)(flashAddr & ((END_FLASH-1) ^ (ERASE_FLASH_BLOCKSIZE-1)));
    uint8_t offset = (uint8_t)(flashAddr & (ERASE_FLASH_BLOCKSIZE-1));
    uint8_t i;

    // Entire row will be erased, read and save the existing data
    for (i=0; i<ERASE_FLASH_BLOCKSIZE; i++)
    {
        ramBuf[i] = FLASH_ReadWord((blockStartAddr+i));
    }

    // Write at offset
    ramBuf[offset] = word;

    // Writes ramBuf to current block
    FLASH_WriteBlock(blockStartAddr, ramBuf);
}

int8_t FLASH_WriteBlock(uint16_t writeAddr, uint16_t *flashWordArray)
{
    uint16_t    blockStartAddr  = (uint16_t )(writeAddr & ((END_FLASH-1) ^ (ERASE_FLASH_BLOCKSIZE-1)));
    uint8_t     GIEBitValue = INTCONbits.GIE;   // Save interrupt enable
    uint8_t i;

    // Flash write must start at the beginning of a row
    if( writeAddr != blockStartAddr )
    {
        return -1;
    }

    INTCONbits.GIE = 0;     // Disble interrupts

    // Block erase sequence
    FLASH_EraseBlock(writeAddr);

    // Block write sequence
    EECON1bits.EEPGD = 1;   // Select Program Memory
    EECON1bits.CFGS = 0;    // Deselect Configuration space
    EECON1bits.WREN = 1;    // Enable wrties
    EECON1bits.LWLO = 1;    // Only load write latches

    for (i=0; i<WRITE_FLASH_BLOCKSIZE; i++)
    {
        // Load lower 8 bits of write address
        EEADRL = (writeAddr & 0xFF);
        // Load upper 6 bits of write address
        EEADRH = ((writeAddr & 0xFF00) >> 8);

        // Load data in current address
        EEDATL = flashWordArray[i];
        EEDATH = ((flashWordArray[i] & 0xFF00) >> 8);

        if(i == (WRITE_FLASH_BLOCKSIZE-1))
        {
            // Start Flash program memory write
            EECON1bits.LWLO = 0;
        }

        EECON2 = 0x55;
        EECON2 = 0xAA;
        EECON1bits.WR = 1;
        NOP();
        NOP();

        writeAddr++;
    }

    EECON1bits.WREN = 0; // Disable writes
    INTCONbits.GIE = GIEBitValue;   // Restore interrupt enable

    return 0;
}

void FLASH_EraseBlock(uint16_t startAddr)
{
    uint8_t GIEBitValue = INTCONbits.GIE;   // Save interrupt enable

    INTCONbits.GIE = 0;     // Disable interrupts
    // Load lower 8 bits of erase address boundary
    EEADRL = (startAddr & 0xFF);
    // Load upper 6 bits of erase address boundary
    EEADRH = ((startAddr & 0xFF00) >> 8);

    // Block erase sequence
    EECON1bits.CFGS = 0;    // Deselect Configuration space
    EECON1bits.EEPGD = 1;   // Select Program Memory
    EECON1bits.FREE = 1;    // Specify an erase operation
    EECON1bits.WREN = 1;    // Allows erase cycles

    // Start of required sequence to initiate erase
    EECON2 = 0x55;
    EECON2 = 0xAA;
    EECON1bits.WR = 1;      // Set WR bit to begin erase
    NOP();
    NOP();

    EECON1bits.WREN = 0;       // Disable writes
    INTCONbits.GIE = GIEBitValue;   // Restore interrupt enable
}

/**
  Section: Data EEPROM Module APIs
*/

void DATAEE_WriteByte(uint8_t bAdd, uint8_t bData)
{
    uint8_t GIEBitValue = 0;

    EEADRL = (bAdd & 0x0ff);    // Data Memory Address to write
    EEDATL = bData;             // Data Memory Value to write
    EECON1bits.EEPGD = 0;   // Point to DATA memory
    EECON1bits.CFGS = 0;        // Deselect Configuration space
    EECON1bits.WREN = 1;        // Enable writes

    GIEBitValue = INTCONbits.GIE;
    INTCONbits.GIE = 0;     // Disable INTs
    EECON2 = 0x55;
    EECON2 = 0xAA;
    EECON1bits.WR = 1;      // Set WR bit to begin write
    // Wait for write to complete
    while (EECON1bits.WR)
    {
    }

    EECON1bits.WREN = 0;    // Disable writes
    INTCONbits.GIE = GIEBitValue;
}

uint8_t DATAEE_ReadByte(uint8_t bAdd)
{
    EEADRL = (bAdd & 0x0ff);    // Data Memory Address to read
    EECON1bits.CFGS = 0;    // Deselect Configuration space
    EECON1bits.EEPGD = 0;   // Point to DATA memory
    EECON1bits.RD = 1;      // EE Read
    NOP();  // NOPs may be required for latency at high frequencies
    NOP();

    return (EEDATL);
}
/**
 End of File
*/

lcd.cは既出。

この発振器を局発に使って、エアバンド受信機キットを組み立て改造中。nobcha23.hatenadiary.com
This generator is combined with air band receiver kit as a local oscillator.